Repository: ashishkumar822/Jetson-SLAM
Branch: master
Commit: 6d47378bf40d
Files: 950
Total size: 8.7 MB
Directory structure:
gitextract_tv5cnj3x/
├── .gitignore
├── CMakeLists.txt
├── Examples/
│ ├── Monocular/
│ │ ├── EuRoC.yaml
│ │ ├── EuRoC_TimeStamps/
│ │ │ ├── MH01.txt
│ │ │ ├── MH02.txt
│ │ │ ├── MH03.txt
│ │ │ ├── MH04.txt
│ │ │ ├── MH05.txt
│ │ │ ├── V101.txt
│ │ │ ├── V102.txt
│ │ │ ├── V103.txt
│ │ │ ├── V201.txt
│ │ │ ├── V202.txt
│ │ │ └── V203.txt
│ │ ├── KITTI00-02.yaml
│ │ ├── KITTI03.yaml
│ │ ├── KITTI04-12.yaml
│ │ ├── TUM1.yaml
│ │ ├── TUM2.yaml
│ │ ├── TUM3.yaml
│ │ ├── mono_euroc
│ │ ├── mono_euroc.cpp
│ │ ├── mono_kitti
│ │ ├── mono_kitti.cpp
│ │ ├── mono_live
│ │ ├── mono_live.cpp
│ │ ├── mono_tum
│ │ └── mono_tum.cpp
│ ├── RGB-D/
│ │ ├── TUM1.yaml
│ │ ├── TUM1_GPU.yaml
│ │ ├── TUM2.yaml
│ │ ├── TUM3.yaml
│ │ ├── associations/
│ │ │ ├── fr1_desk.txt
│ │ │ ├── fr1_desk2.txt
│ │ │ ├── fr1_room.txt
│ │ │ ├── fr1_xyz.txt
│ │ │ ├── fr2_desk.txt
│ │ │ ├── fr2_xyz.txt
│ │ │ ├── fr3_nstr_tex_near.txt
│ │ │ ├── fr3_office.txt
│ │ │ ├── fr3_office_val.txt
│ │ │ ├── fr3_str_tex_far.txt
│ │ │ └── fr3_str_tex_near.txt
│ │ ├── kinect.yaml
│ │ ├── rgbd_live
│ │ ├── rgbd_live.cpp
│ │ ├── rgbd_live.yaml
│ │ ├── rgbd_tum
│ │ └── rgbd_tum.cpp
│ └── Stereo/
│ ├── EuRoC.yaml
│ ├── EuRoC_TimeStamps/
│ │ ├── MH01.txt
│ │ ├── MH02.txt
│ │ ├── MH03.txt
│ │ ├── MH04.txt
│ │ ├── MH05.txt
│ │ ├── V101.txt
│ │ ├── V102.txt
│ │ ├── V103.txt
│ │ ├── V201.txt
│ │ ├── V202.txt
│ │ └── V203.txt
│ ├── KITTI00-02.yaml
│ ├── KITTI00-02_custom.yaml
│ ├── KITTI03.yaml
│ ├── KITTI04-12.yaml
│ ├── euroc_old/
│ │ ├── CameraTrajectory_MH01.txt
│ │ ├── CameraTrajectory_MH02.txt
│ │ ├── CameraTrajectory_MH03.txt
│ │ ├── CameraTrajectory_MH04.txt
│ │ └── CameraTrajectory_MH05.txt
│ ├── kaist_vio_dataset.yaml
│ ├── stereo_euroc
│ ├── stereo_euroc.cpp
│ ├── stereo_kitti
│ ├── stereo_kitti.cpp
│ ├── stereo_live
│ ├── stereo_live.cpp
│ └── stereo_rig_realsense.yaml
├── README.md
├── Thirdparty/
│ ├── DBoW2/
│ │ ├── CMakeLists.txt
│ │ ├── DBoW2/
│ │ │ ├── BowVector.cpp
│ │ │ ├── BowVector.h
│ │ │ ├── FClass.h
│ │ │ ├── FORB.cpp
│ │ │ ├── FORB.h
│ │ │ ├── FeatureVector.cpp
│ │ │ ├── FeatureVector.h
│ │ │ ├── ScoringObject.cpp
│ │ │ ├── ScoringObject.h
│ │ │ └── TemplatedVocabulary.h
│ │ ├── DUtils/
│ │ │ ├── Random.cpp
│ │ │ ├── Random.h
│ │ │ ├── Timestamp.cpp
│ │ │ └── Timestamp.h
│ │ ├── LICENSE.txt
│ │ └── README.txt
│ ├── g2o/
│ │ ├── CMakeLists.txt
│ │ ├── README.txt
│ │ ├── cmake_modules/
│ │ │ ├── FindBLAS.cmake
│ │ │ ├── FindEigen3.cmake
│ │ │ └── FindLAPACK.cmake
│ │ ├── config.h
│ │ ├── config.h.in
│ │ ├── g2o/
│ │ │ ├── core/
│ │ │ │ ├── base_binary_edge.h
│ │ │ │ ├── base_binary_edge.hpp
│ │ │ │ ├── base_edge.h
│ │ │ │ ├── base_multi_edge.h
│ │ │ │ ├── base_multi_edge.hpp
│ │ │ │ ├── base_unary_edge.h
│ │ │ │ ├── base_unary_edge.hpp
│ │ │ │ ├── base_vertex.h
│ │ │ │ ├── base_vertex.hpp
│ │ │ │ ├── batch_stats.cpp
│ │ │ │ ├── batch_stats.h
│ │ │ │ ├── block_solver.h
│ │ │ │ ├── block_solver.hpp
│ │ │ │ ├── cache.cpp
│ │ │ │ ├── cache.h
│ │ │ │ ├── creators.h
│ │ │ │ ├── eigen_types.h
│ │ │ │ ├── estimate_propagator.cpp
│ │ │ │ ├── estimate_propagator.h
│ │ │ │ ├── factory.cpp
│ │ │ │ ├── factory.h
│ │ │ │ ├── hyper_dijkstra.cpp
│ │ │ │ ├── hyper_dijkstra.h
│ │ │ │ ├── hyper_graph.cpp
│ │ │ │ ├── hyper_graph.h
│ │ │ │ ├── hyper_graph_action.cpp
│ │ │ │ ├── hyper_graph_action.h
│ │ │ │ ├── jacobian_workspace.cpp
│ │ │ │ ├── jacobian_workspace.h
│ │ │ │ ├── linear_solver.h
│ │ │ │ ├── marginal_covariance_cholesky.cpp
│ │ │ │ ├── marginal_covariance_cholesky.h
│ │ │ │ ├── matrix_operations.h
│ │ │ │ ├── matrix_structure.cpp
│ │ │ │ ├── matrix_structure.h
│ │ │ │ ├── openmp_mutex.h
│ │ │ │ ├── optimizable_graph.cpp
│ │ │ │ ├── optimizable_graph.h
│ │ │ │ ├── optimization_algorithm.cpp
│ │ │ │ ├── optimization_algorithm.h
│ │ │ │ ├── optimization_algorithm_dogleg.cpp
│ │ │ │ ├── optimization_algorithm_dogleg.h
│ │ │ │ ├── optimization_algorithm_factory.cpp
│ │ │ │ ├── optimization_algorithm_factory.h
│ │ │ │ ├── optimization_algorithm_gauss_newton.cpp
│ │ │ │ ├── optimization_algorithm_gauss_newton.h
│ │ │ │ ├── optimization_algorithm_levenberg.cpp
│ │ │ │ ├── optimization_algorithm_levenberg.h
│ │ │ │ ├── optimization_algorithm_property.h
│ │ │ │ ├── optimization_algorithm_with_hessian.cpp
│ │ │ │ ├── optimization_algorithm_with_hessian.h
│ │ │ │ ├── parameter.cpp
│ │ │ │ ├── parameter.h
│ │ │ │ ├── parameter_container.cpp
│ │ │ │ ├── parameter_container.h
│ │ │ │ ├── robust_kernel.cpp
│ │ │ │ ├── robust_kernel.h
│ │ │ │ ├── robust_kernel_factory.cpp
│ │ │ │ ├── robust_kernel_factory.h
│ │ │ │ ├── robust_kernel_impl.cpp
│ │ │ │ ├── robust_kernel_impl.h
│ │ │ │ ├── solver.cpp
│ │ │ │ ├── solver.h
│ │ │ │ ├── sparse_block_matrix.h
│ │ │ │ ├── sparse_block_matrix.hpp
│ │ │ │ ├── sparse_block_matrix_ccs.h
│ │ │ │ ├── sparse_block_matrix_diagonal.h
│ │ │ │ ├── sparse_block_matrix_test.cpp
│ │ │ │ ├── sparse_optimizer.cpp
│ │ │ │ └── sparse_optimizer.h
│ │ │ ├── solvers/
│ │ │ │ ├── linear_solver_dense.h
│ │ │ │ └── linear_solver_eigen.h
│ │ │ ├── stuff/
│ │ │ │ ├── color_macros.h
│ │ │ │ ├── macros.h
│ │ │ │ ├── misc.h
│ │ │ │ ├── os_specific.c
│ │ │ │ ├── os_specific.h
│ │ │ │ ├── property.cpp
│ │ │ │ ├── property.h
│ │ │ │ ├── string_tools.cpp
│ │ │ │ ├── string_tools.h
│ │ │ │ ├── timeutil.cpp
│ │ │ │ └── timeutil.h
│ │ │ └── types/
│ │ │ ├── se3_ops.h
│ │ │ ├── se3_ops.hpp
│ │ │ ├── se3quat.h
│ │ │ ├── sim3.h
│ │ │ ├── types_sba.cpp
│ │ │ ├── types_sba.h
│ │ │ ├── types_seven_dof_expmap.cpp
│ │ │ ├── types_seven_dof_expmap.h
│ │ │ ├── types_six_dof_expmap.cpp
│ │ │ └── types_six_dof_expmap.h
│ │ └── license-bsd.txt
│ └── g2o_new/
│ ├── CMakeLists.txt
│ ├── Makefile
│ ├── README.md
│ ├── benchmarks/
│ │ ├── CMakeLists.txt
│ │ └── jacobian_timing_tests.cpp
│ ├── cmake_modules/
│ │ ├── CheckIfUnderscorePrefixedBesselFunctionsExist.cmake
│ │ ├── Config.cmake.in
│ │ ├── FindCSparse.cmake
│ │ ├── FindEigen3.cmake
│ │ ├── FindG2O.cmake
│ │ ├── FindMETIS.cmake
│ │ ├── FindQGLViewer.cmake
│ │ └── FindSuiteSparse.cmake
│ ├── codecov.yml
│ ├── config.h
│ ├── config.h.in
│ ├── doc/
│ │ ├── .gitignore
│ │ ├── Makefile
│ │ ├── README_IF_IT_WAS_WORKING_AND_IT_DOES_NOT.txt
│ │ ├── doxygen/
│ │ │ ├── doxy.config
│ │ │ └── readme.txt
│ │ ├── g2o.tex
│ │ ├── license-bsd.txt
│ │ ├── license-gpl.txt
│ │ ├── license-lgpl.txt
│ │ ├── pics/
│ │ │ ├── classes.fig
│ │ │ ├── hgraph.fig
│ │ │ └── slam.fig
│ │ └── robots.bib
│ ├── g2o/
│ │ ├── .gitignore
│ │ ├── CMakeLists.txt
│ │ ├── EXTERNAL/
│ │ │ ├── CMakeLists.txt
│ │ │ └── freeglut/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── COPYING
│ │ │ ├── freeglut_font.cpp
│ │ │ ├── freeglut_minimal.h
│ │ │ ├── freeglut_stroke_mono_roman.cpp
│ │ │ └── freeglut_stroke_roman.cpp
│ │ ├── apps/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── g2o_cli/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── dl_wrapper.cpp
│ │ │ │ ├── dl_wrapper.h
│ │ │ │ ├── g2o.cpp
│ │ │ │ ├── g2o_cli_api.h
│ │ │ │ ├── g2o_common.cpp
│ │ │ │ ├── g2o_common.h
│ │ │ │ ├── output_helper.cpp
│ │ │ │ └── output_helper.h
│ │ │ ├── g2o_simulator/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── g2o_simulator_api.h
│ │ │ │ ├── pointsensorparameters.cpp
│ │ │ │ ├── pointsensorparameters.h
│ │ │ │ ├── sensor_line3d.cpp
│ │ │ │ ├── sensor_line3d.h
│ │ │ │ ├── sensor_odometry.h
│ │ │ │ ├── sensor_odometry2d.cpp
│ │ │ │ ├── sensor_odometry2d.h
│ │ │ │ ├── sensor_odometry3d.cpp
│ │ │ │ ├── sensor_odometry3d.h
│ │ │ │ ├── sensor_pointxy.cpp
│ │ │ │ ├── sensor_pointxy.h
│ │ │ │ ├── sensor_pointxy_bearing.cpp
│ │ │ │ ├── sensor_pointxy_bearing.h
│ │ │ │ ├── sensor_pointxy_offset.cpp
│ │ │ │ ├── sensor_pointxy_offset.h
│ │ │ │ ├── sensor_pointxyz.cpp
│ │ │ │ ├── sensor_pointxyz.h
│ │ │ │ ├── sensor_pointxyz_depth.cpp
│ │ │ │ ├── sensor_pointxyz_depth.h
│ │ │ │ ├── sensor_pointxyz_disparity.cpp
│ │ │ │ ├── sensor_pointxyz_disparity.h
│ │ │ │ ├── sensor_pose2d.cpp
│ │ │ │ ├── sensor_pose2d.h
│ │ │ │ ├── sensor_pose3d.cpp
│ │ │ │ ├── sensor_pose3d.h
│ │ │ │ ├── sensor_pose3d_offset.cpp
│ │ │ │ ├── sensor_pose3d_offset.h
│ │ │ │ ├── sensor_se3_prior.cpp
│ │ │ │ ├── sensor_se3_prior.h
│ │ │ │ ├── sensor_segment2d.cpp
│ │ │ │ ├── sensor_segment2d.h
│ │ │ │ ├── sensor_segment2d_line.cpp
│ │ │ │ ├── sensor_segment2d_line.h
│ │ │ │ ├── sensor_segment2d_pointline.cpp
│ │ │ │ ├── sensor_segment2d_pointline.h
│ │ │ │ ├── simulator.cpp
│ │ │ │ ├── simulator.h
│ │ │ │ ├── simulator2d.h
│ │ │ │ ├── simulator2d_base.h
│ │ │ │ ├── simulator2d_segment.cpp
│ │ │ │ ├── simulator3d.h
│ │ │ │ ├── simulator3d_base.h
│ │ │ │ ├── simutils.cpp
│ │ │ │ ├── simutils.h
│ │ │ │ ├── test_simulator2d.cpp
│ │ │ │ └── test_simulator3d.cpp
│ │ │ ├── g2o_viewer/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── base_main_window.ui
│ │ │ │ ├── base_properties_widget.ui
│ │ │ │ ├── g2o_qglviewer.cpp
│ │ │ │ ├── g2o_qglviewer.h
│ │ │ │ ├── g2o_viewer.cpp
│ │ │ │ ├── g2o_viewer_api.h
│ │ │ │ ├── gui_hyper_graph_action.cpp
│ │ │ │ ├── gui_hyper_graph_action.h
│ │ │ │ ├── main_window.cpp
│ │ │ │ ├── main_window.h
│ │ │ │ ├── properties_widget.cpp
│ │ │ │ ├── properties_widget.h
│ │ │ │ ├── run_g2o_viewer.cpp
│ │ │ │ ├── run_g2o_viewer.h
│ │ │ │ ├── stream_redirect.cpp
│ │ │ │ ├── stream_redirect.h
│ │ │ │ ├── viewer_properties_widget.cpp
│ │ │ │ └── viewer_properties_widget.h
│ │ │ └── linked_binaries/
│ │ │ └── CMakeLists.txt
│ │ ├── autodiff/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── LICENSE
│ │ │ ├── array_selector.h
│ │ │ ├── autodiff.h
│ │ │ ├── disable_warnings.h
│ │ │ ├── eigen.h
│ │ │ ├── fixed_array.h
│ │ │ ├── integer_sequence_algorithm.h
│ │ │ ├── jet.h
│ │ │ ├── memory.h
│ │ │ ├── parameter_dims.h
│ │ │ ├── reenable_warnings.h
│ │ │ ├── types.h
│ │ │ └── variadic_evaluate.h
│ │ ├── core/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── auto_differentiation.h
│ │ │ ├── base_binary_edge.h
│ │ │ ├── base_dynamic_vertex.h
│ │ │ ├── base_edge.h
│ │ │ ├── base_fixed_sized_edge.h
│ │ │ ├── base_fixed_sized_edge.hpp
│ │ │ ├── base_multi_edge.h
│ │ │ ├── base_unary_edge.h
│ │ │ ├── base_variable_sized_edge.h
│ │ │ ├── base_variable_sized_edge.hpp
│ │ │ ├── base_vertex.h
│ │ │ ├── base_vertex.hpp
│ │ │ ├── batch_stats.cpp
│ │ │ ├── batch_stats.h
│ │ │ ├── block_solver.h
│ │ │ ├── block_solver.hpp
│ │ │ ├── cache.cpp
│ │ │ ├── cache.h
│ │ │ ├── creators.h
│ │ │ ├── dynamic_aligned_buffer.hpp
│ │ │ ├── eigen_types.h
│ │ │ ├── estimate_propagator.cpp
│ │ │ ├── estimate_propagator.h
│ │ │ ├── factory.cpp
│ │ │ ├── factory.h
│ │ │ ├── g2o_core_api.h
│ │ │ ├── hyper_dijkstra.cpp
│ │ │ ├── hyper_dijkstra.h
│ │ │ ├── hyper_graph.cpp
│ │ │ ├── hyper_graph.h
│ │ │ ├── hyper_graph_action.cpp
│ │ │ ├── hyper_graph_action.h
│ │ │ ├── io_helper.h
│ │ │ ├── jacobian_workspace.cpp
│ │ │ ├── jacobian_workspace.h
│ │ │ ├── linear_solver.h
│ │ │ ├── marginal_covariance_cholesky.cpp
│ │ │ ├── marginal_covariance_cholesky.h
│ │ │ ├── matrix_operations.h
│ │ │ ├── matrix_structure.cpp
│ │ │ ├── matrix_structure.h
│ │ │ ├── openmp_mutex.h
│ │ │ ├── optimizable_graph.cpp
│ │ │ ├── optimizable_graph.h
│ │ │ ├── optimization_algorithm.cpp
│ │ │ ├── optimization_algorithm.h
│ │ │ ├── optimization_algorithm_dogleg.cpp
│ │ │ ├── optimization_algorithm_dogleg.h
│ │ │ ├── optimization_algorithm_factory.cpp
│ │ │ ├── optimization_algorithm_factory.h
│ │ │ ├── optimization_algorithm_gauss_newton.cpp
│ │ │ ├── optimization_algorithm_gauss_newton.h
│ │ │ ├── optimization_algorithm_levenberg.cpp
│ │ │ ├── optimization_algorithm_levenberg.h
│ │ │ ├── optimization_algorithm_property.h
│ │ │ ├── optimization_algorithm_with_hessian.cpp
│ │ │ ├── optimization_algorithm_with_hessian.h
│ │ │ ├── ownership.h
│ │ │ ├── parameter.cpp
│ │ │ ├── parameter.h
│ │ │ ├── parameter_container.cpp
│ │ │ ├── parameter_container.h
│ │ │ ├── robust_kernel.cpp
│ │ │ ├── robust_kernel.h
│ │ │ ├── robust_kernel_factory.cpp
│ │ │ ├── robust_kernel_factory.h
│ │ │ ├── robust_kernel_impl.cpp
│ │ │ ├── robust_kernel_impl.h
│ │ │ ├── solver.cpp
│ │ │ ├── solver.h
│ │ │ ├── sparse_block_matrix.h
│ │ │ ├── sparse_block_matrix.hpp
│ │ │ ├── sparse_block_matrix_ccs.h
│ │ │ ├── sparse_block_matrix_diagonal.h
│ │ │ ├── sparse_optimizer.cpp
│ │ │ ├── sparse_optimizer.h
│ │ │ ├── sparse_optimizer_terminate_action.cpp
│ │ │ └── sparse_optimizer_terminate_action.h
│ │ ├── examples/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── anonymize_observations/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── g2o_anonymize_observations.cpp
│ │ │ ├── ba/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── ba_demo.cpp
│ │ │ ├── ba_anchored_inverse_depth/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── ba_anchored_inverse_depth_demo.cpp
│ │ │ ├── bal/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── bal_example.cpp
│ │ │ ├── calibration_odom_laser/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── closed_form_calibration.cpp
│ │ │ │ ├── closed_form_calibration.h
│ │ │ │ ├── edge_se2_pure_calib.cpp
│ │ │ │ ├── edge_se2_pure_calib.h
│ │ │ │ ├── g2o_calibration_odom_laser_api.h
│ │ │ │ ├── gm2dl_io.cpp
│ │ │ │ ├── gm2dl_io.h
│ │ │ │ ├── motion_information.h
│ │ │ │ ├── sclam_helpers.cpp
│ │ │ │ ├── sclam_helpers.h
│ │ │ │ ├── sclam_laser_calib.cpp
│ │ │ │ ├── sclam_odom_laser.cpp
│ │ │ │ └── sclam_pure_calibration.cpp
│ │ │ ├── convert_segment_line/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── convertSegmentLine.cpp
│ │ │ ├── data_convert/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── convert_sba_slam3d.cpp
│ │ │ ├── data_fitting/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── circle_fit.cpp
│ │ │ │ └── curve_fit.cpp
│ │ │ ├── dynamic_vertex/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── polynomial_fit.cpp
│ │ │ │ └── static_dynamic_function_fit.cpp
│ │ │ ├── g2o_hierarchical/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── backbone_tree_action.cpp
│ │ │ │ ├── backbone_tree_action.h
│ │ │ │ ├── edge_creator.cpp
│ │ │ │ ├── edge_creator.h
│ │ │ │ ├── edge_labeler.cpp
│ │ │ │ ├── edge_labeler.h
│ │ │ │ ├── edge_types_cost_function.cpp
│ │ │ │ ├── edge_types_cost_function.h
│ │ │ │ ├── g2o_hierarchical.cpp
│ │ │ │ ├── g2o_hierarchical_api.h
│ │ │ │ ├── simple_star_ops.cpp
│ │ │ │ ├── simple_star_ops.h
│ │ │ │ ├── star.cpp
│ │ │ │ └── star.h
│ │ │ ├── icp/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── gicp_demo.cpp
│ │ │ │ └── gicp_sba_demo.cpp
│ │ │ ├── interactive_slam/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── README.txt
│ │ │ │ ├── g2o_incremental/
│ │ │ │ │ ├── CMakeLists.txt
│ │ │ │ │ ├── README.txt
│ │ │ │ │ ├── g2o_incremental.cpp
│ │ │ │ │ ├── g2o_incremental_api.h
│ │ │ │ │ ├── graph_optimizer_sparse_incremental.cpp
│ │ │ │ │ ├── graph_optimizer_sparse_incremental.h
│ │ │ │ │ ├── linear_solver_cholmod_online.h
│ │ │ │ │ └── protocol.txt
│ │ │ │ ├── g2o_interactive/
│ │ │ │ │ ├── CMakeLists.txt
│ │ │ │ │ ├── fast_output.h
│ │ │ │ │ ├── g2o_interactive_api.h
│ │ │ │ │ ├── g2o_online.cpp
│ │ │ │ │ ├── g2o_slam_interface.cpp
│ │ │ │ │ ├── g2o_slam_interface.h
│ │ │ │ │ ├── generate_commands.cpp
│ │ │ │ │ ├── graph_optimizer_sparse_online.cpp
│ │ │ │ │ ├── graph_optimizer_sparse_online.h
│ │ │ │ │ ├── protocol.txt
│ │ │ │ │ ├── types_online.cpp
│ │ │ │ │ ├── types_slam2d_online.h
│ │ │ │ │ └── types_slam3d_online.h
│ │ │ │ └── slam_parser/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── example/
│ │ │ │ │ ├── CMakeLists.txt
│ │ │ │ │ ├── example_slam_interface.cpp
│ │ │ │ │ ├── example_slam_interface.h
│ │ │ │ │ └── test_slam_interface.cpp
│ │ │ │ ├── interface/
│ │ │ │ │ ├── CMakeLists.txt
│ │ │ │ │ ├── abstract_slam_interface.h
│ │ │ │ │ ├── parser_interface.cpp
│ │ │ │ │ ├── parser_interface.h
│ │ │ │ │ ├── slam_context_interface.cpp
│ │ │ │ │ └── slam_context_interface.h
│ │ │ │ └── parser/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── FlexLexer.h
│ │ │ │ ├── bison_parser.cpp
│ │ │ │ ├── bison_parser.h
│ │ │ │ ├── commands.h
│ │ │ │ ├── driver.cpp
│ │ │ │ ├── driver.h
│ │ │ │ ├── flex_scanner.cpp
│ │ │ │ ├── grammar.sh
│ │ │ │ ├── location.hh
│ │ │ │ ├── parser.yy
│ │ │ │ ├── position.hh
│ │ │ │ ├── scanner.h
│ │ │ │ ├── scanner.l
│ │ │ │ ├── slam_context.cpp
│ │ │ │ ├── slam_context.h
│ │ │ │ └── test_slam_parser.cpp
│ │ │ ├── line_slam/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── line_test.cpp
│ │ │ │ └── simulator_3d_line.cpp
│ │ │ ├── logging/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── logging.cpp
│ │ │ ├── plane_slam/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── plane_test.cpp
│ │ │ │ └── simulator_3d_plane.cpp
│ │ │ ├── sba/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── sba_demo.cpp
│ │ │ ├── sim3/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── optimize_sphere_by_sim3.cpp
│ │ │ ├── simple_optimize/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── simple_optimize.cpp
│ │ │ ├── slam2d/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── base_main_window.ui
│ │ │ │ ├── main_window.cpp
│ │ │ │ ├── main_window.h
│ │ │ │ ├── slam2d_g2o.cpp
│ │ │ │ ├── slam2d_viewer.cpp
│ │ │ │ └── slam2d_viewer.h
│ │ │ ├── sphere/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── create_sphere.cpp
│ │ │ ├── target/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── constant_velocity_target.cpp
│ │ │ │ ├── continuous_to_discrete.h
│ │ │ │ ├── static_target.cpp
│ │ │ │ ├── targetTypes3D.hpp
│ │ │ │ └── targetTypes6D.hpp
│ │ │ └── tutorial_slam2d/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── edge_se2.cpp
│ │ │ ├── edge_se2.h
│ │ │ ├── edge_se2_pointxy.cpp
│ │ │ ├── edge_se2_pointxy.h
│ │ │ ├── g2o_tutorial_slam2d_api.h
│ │ │ ├── parameter_se2_offset.cpp
│ │ │ ├── parameter_se2_offset.h
│ │ │ ├── se2.h
│ │ │ ├── simulator.cpp
│ │ │ ├── simulator.h
│ │ │ ├── tutorial_slam2d.cpp
│ │ │ ├── types_tutorial_slam2d.cpp
│ │ │ ├── types_tutorial_slam2d.h
│ │ │ ├── vertex_point_xy.cpp
│ │ │ ├── vertex_point_xy.h
│ │ │ ├── vertex_se2.cpp
│ │ │ └── vertex_se2.h
│ │ ├── solvers/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── cholmod/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── cholmod_ext.h
│ │ │ │ ├── cholmod_wrapper.cpp
│ │ │ │ ├── cholmod_wrapper.h
│ │ │ │ ├── linear_solver_cholmod.h
│ │ │ │ └── solver_cholmod.cpp
│ │ │ ├── csparse/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── csparse_extension.cpp
│ │ │ │ ├── csparse_extension.h
│ │ │ │ ├── csparse_helper.cpp
│ │ │ │ ├── csparse_helper.h
│ │ │ │ ├── csparse_wrapper.cpp
│ │ │ │ ├── csparse_wrapper.h
│ │ │ │ ├── g2o_csparse_api.h
│ │ │ │ ├── g2o_csparse_extension_api.h
│ │ │ │ ├── linear_solver_csparse.h
│ │ │ │ └── solver_csparse.cpp
│ │ │ ├── dense/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── linear_solver_dense.h
│ │ │ │ └── solver_dense.cpp
│ │ │ ├── eigen/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── linear_solver_eigen.h
│ │ │ │ └── solver_eigen.cpp
│ │ │ ├── pcg/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── linear_solver_pcg.h
│ │ │ │ ├── linear_solver_pcg.hpp
│ │ │ │ └── solver_pcg.cpp
│ │ │ ├── slam2d_linear/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── g2o_slam2d_linear_api.h
│ │ │ │ ├── slam2d_linear.cpp
│ │ │ │ ├── solver_slam2d_linear.cpp
│ │ │ │ └── solver_slam2d_linear.h
│ │ │ └── structure_only/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── structure_only.cpp
│ │ │ └── structure_only_solver.h
│ │ ├── stuff/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── color_macros.h
│ │ │ ├── command_args.cpp
│ │ │ ├── command_args.h
│ │ │ ├── filesys_tools.cpp
│ │ │ ├── filesys_tools.h
│ │ │ ├── g2o_stuff_api.h
│ │ │ ├── logger.cpp
│ │ │ ├── logger.h
│ │ │ ├── logger_format.h
│ │ │ ├── macros.h
│ │ │ ├── misc.h
│ │ │ ├── opengl_primitives.cpp
│ │ │ ├── opengl_primitives.h
│ │ │ ├── opengl_wrapper.h
│ │ │ ├── property.cpp
│ │ │ ├── property.h
│ │ │ ├── sampler.cpp
│ │ │ ├── sampler.h
│ │ │ ├── sparse_helper.cpp
│ │ │ ├── sparse_helper.h
│ │ │ ├── string_tools.cpp
│ │ │ ├── string_tools.h
│ │ │ ├── tictoc.cpp
│ │ │ ├── tictoc.h
│ │ │ ├── timeutil.cpp
│ │ │ ├── timeutil.h
│ │ │ ├── tuple_tools.h
│ │ │ └── unscented.h
│ │ ├── types/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── data/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── data_queue.cpp
│ │ │ │ ├── data_queue.h
│ │ │ │ ├── g2o_types_data_api.h
│ │ │ │ ├── laser_parameters.cpp
│ │ │ │ ├── laser_parameters.h
│ │ │ │ ├── raw_laser.cpp
│ │ │ │ ├── raw_laser.h
│ │ │ │ ├── robot_data.cpp
│ │ │ │ ├── robot_data.h
│ │ │ │ ├── robot_laser.cpp
│ │ │ │ ├── robot_laser.h
│ │ │ │ ├── types_data.cpp
│ │ │ │ ├── types_data.h
│ │ │ │ ├── vertex_ellipse.cpp
│ │ │ │ ├── vertex_ellipse.h
│ │ │ │ ├── vertex_tag.cpp
│ │ │ │ └── vertex_tag.h
│ │ │ ├── icp/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── g2o_types_icp_api.h
│ │ │ │ ├── types_icp.cpp
│ │ │ │ └── types_icp.h
│ │ │ ├── sba/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── edge_project_p2mc.cpp
│ │ │ │ ├── edge_project_p2mc.h
│ │ │ │ ├── edge_project_p2sc.cpp
│ │ │ │ ├── edge_project_p2sc.h
│ │ │ │ ├── edge_project_psi2uv.cpp
│ │ │ │ ├── edge_project_psi2uv.h
│ │ │ │ ├── edge_project_stereo_xyz.cpp
│ │ │ │ ├── edge_project_stereo_xyz.h
│ │ │ │ ├── edge_project_stereo_xyz_onlypose.cpp
│ │ │ │ ├── edge_project_stereo_xyz_onlypose.h
│ │ │ │ ├── edge_project_xyz.cpp
│ │ │ │ ├── edge_project_xyz.h
│ │ │ │ ├── edge_project_xyz2uv.cpp
│ │ │ │ ├── edge_project_xyz2uv.h
│ │ │ │ ├── edge_project_xyz2uvu.cpp
│ │ │ │ ├── edge_project_xyz2uvu.h
│ │ │ │ ├── edge_project_xyz_onlypose.cpp
│ │ │ │ ├── edge_project_xyz_onlypose.h
│ │ │ │ ├── edge_sba_cam.cpp
│ │ │ │ ├── edge_sba_cam.h
│ │ │ │ ├── edge_sba_scale.cpp
│ │ │ │ ├── edge_sba_scale.h
│ │ │ │ ├── edge_se3_expmap.cpp
│ │ │ │ ├── edge_se3_expmap.h
│ │ │ │ ├── g2o_types_sba_api.h
│ │ │ │ ├── parameter_cameraparameters.cpp
│ │ │ │ ├── parameter_cameraparameters.h
│ │ │ │ ├── sba_utils.h
│ │ │ │ ├── sbacam.cpp
│ │ │ │ ├── sbacam.h
│ │ │ │ ├── types_sba.cpp
│ │ │ │ ├── types_sba.h
│ │ │ │ ├── types_six_dof_expmap.cpp
│ │ │ │ ├── types_six_dof_expmap.h
│ │ │ │ ├── vertex_cam.cpp
│ │ │ │ ├── vertex_cam.h
│ │ │ │ ├── vertex_intrinsics.cpp
│ │ │ │ ├── vertex_intrinsics.h
│ │ │ │ ├── vertex_se3_expmap.cpp
│ │ │ │ └── vertex_se3_expmap.h
│ │ │ ├── sclam2d/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── edge_se2_odom_differential_calib.cpp
│ │ │ │ ├── edge_se2_odom_differential_calib.h
│ │ │ │ ├── edge_se2_sensor_calib.cpp
│ │ │ │ ├── edge_se2_sensor_calib.h
│ │ │ │ ├── g2o_types_sclam2d_api.h
│ │ │ │ ├── odometry_measurement.cpp
│ │ │ │ ├── odometry_measurement.h
│ │ │ │ ├── types_sclam2d.cpp
│ │ │ │ ├── types_sclam2d.h
│ │ │ │ ├── vertex_odom_differential_params.cpp
│ │ │ │ └── vertex_odom_differential_params.h
│ │ │ ├── sim3/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── sim3.h
│ │ │ │ ├── types_seven_dof_expmap.cpp
│ │ │ │ └── types_seven_dof_expmap.h
│ │ │ ├── slam2d/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── edge_pointxy.cpp
│ │ │ │ ├── edge_pointxy.h
│ │ │ │ ├── edge_se2.cpp
│ │ │ │ ├── edge_se2.h
│ │ │ │ ├── edge_se2_lotsofxy.cpp
│ │ │ │ ├── edge_se2_lotsofxy.h
│ │ │ │ ├── edge_se2_offset.cpp
│ │ │ │ ├── edge_se2_offset.h
│ │ │ │ ├── edge_se2_pointxy.cpp
│ │ │ │ ├── edge_se2_pointxy.h
│ │ │ │ ├── edge_se2_pointxy_bearing.cpp
│ │ │ │ ├── edge_se2_pointxy_bearing.h
│ │ │ │ ├── edge_se2_pointxy_calib.cpp
│ │ │ │ ├── edge_se2_pointxy_calib.h
│ │ │ │ ├── edge_se2_pointxy_offset.cpp
│ │ │ │ ├── edge_se2_pointxy_offset.h
│ │ │ │ ├── edge_se2_prior.cpp
│ │ │ │ ├── edge_se2_prior.h
│ │ │ │ ├── edge_se2_twopointsxy.cpp
│ │ │ │ ├── edge_se2_twopointsxy.h
│ │ │ │ ├── edge_se2_xyprior.cpp
│ │ │ │ ├── edge_se2_xyprior.h
│ │ │ │ ├── edge_xy_prior.cpp
│ │ │ │ ├── edge_xy_prior.h
│ │ │ │ ├── g2o_types_slam2d_api.h
│ │ │ │ ├── parameter_se2_offset.cpp
│ │ │ │ ├── parameter_se2_offset.h
│ │ │ │ ├── se2.h
│ │ │ │ ├── types_slam2d.cpp
│ │ │ │ ├── types_slam2d.h
│ │ │ │ ├── vertex_point_xy.cpp
│ │ │ │ ├── vertex_point_xy.h
│ │ │ │ ├── vertex_se2.cpp
│ │ │ │ └── vertex_se2.h
│ │ │ ├── slam2d_addons/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── edge_line2d.cpp
│ │ │ │ ├── edge_line2d.h
│ │ │ │ ├── edge_line2d_pointxy.cpp
│ │ │ │ ├── edge_line2d_pointxy.h
│ │ │ │ ├── edge_se2_line2d.cpp
│ │ │ │ ├── edge_se2_line2d.h
│ │ │ │ ├── edge_se2_segment2d.cpp
│ │ │ │ ├── edge_se2_segment2d.h
│ │ │ │ ├── edge_se2_segment2d_line.cpp
│ │ │ │ ├── edge_se2_segment2d_line.h
│ │ │ │ ├── edge_se2_segment2d_pointLine.cpp
│ │ │ │ ├── edge_se2_segment2d_pointLine.h
│ │ │ │ ├── g2o_types_slam2d_addons_api.h
│ │ │ │ ├── line_2d.h
│ │ │ │ ├── types_slam2d_addons.cpp
│ │ │ │ ├── types_slam2d_addons.h
│ │ │ │ ├── vertex_line2d.cpp
│ │ │ │ ├── vertex_line2d.h
│ │ │ │ ├── vertex_segment2d.cpp
│ │ │ │ └── vertex_segment2d.h
│ │ │ ├── slam3d/
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── dquat2mat.cpp
│ │ │ │ ├── dquat2mat.h
│ │ │ │ ├── dquat2mat.wxm
│ │ │ │ ├── dquat2mat_maxima_generated.cpp
│ │ │ │ ├── edge_pointxyz.cpp
│ │ │ │ ├── edge_pointxyz.h
│ │ │ │ ├── edge_se3.cpp
│ │ │ │ ├── edge_se3.h
│ │ │ │ ├── edge_se3_lotsofxyz.cpp
│ │ │ │ ├── edge_se3_lotsofxyz.h
│ │ │ │ ├── edge_se3_offset.cpp
│ │ │ │ ├── edge_se3_offset.h
│ │ │ │ ├── edge_se3_pointxyz.cpp
│ │ │ │ ├── edge_se3_pointxyz.h
│ │ │ │ ├── edge_se3_pointxyz_depth.cpp
│ │ │ │ ├── edge_se3_pointxyz_depth.h
│ │ │ │ ├── edge_se3_pointxyz_disparity.cpp
│ │ │ │ ├── edge_se3_pointxyz_disparity.h
│ │ │ │ ├── edge_se3_prior.cpp
│ │ │ │ ├── edge_se3_prior.h
│ │ │ │ ├── edge_se3_xyzprior.cpp
│ │ │ │ ├── edge_se3_xyzprior.h
│ │ │ │ ├── edge_xyz_prior.cpp
│ │ │ │ ├── edge_xyz_prior.h
│ │ │ │ ├── g2o_types_slam3d_api.h
│ │ │ │ ├── isometry3d_gradients.cpp
│ │ │ │ ├── isometry3d_gradients.h
│ │ │ │ ├── isometry3d_mappings.cpp
│ │ │ │ ├── isometry3d_mappings.h
│ │ │ │ ├── parameter_camera.cpp
│ │ │ │ ├── parameter_camera.h
│ │ │ │ ├── parameter_se3_offset.cpp
│ │ │ │ ├── parameter_se3_offset.h
│ │ │ │ ├── parameter_stereo_camera.cpp
│ │ │ │ ├── parameter_stereo_camera.h
│ │ │ │ ├── se3_ops.h
│ │ │ │ ├── se3_ops.hpp
│ │ │ │ ├── se3quat.h
│ │ │ │ ├── types_slam3d.cpp
│ │ │ │ ├── types_slam3d.h
│ │ │ │ ├── vertex_pointxyz.cpp
│ │ │ │ ├── vertex_pointxyz.h
│ │ │ │ ├── vertex_se3.cpp
│ │ │ │ └── vertex_se3.h
│ │ │ └── slam3d_addons/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── edge_plane.cpp
│ │ │ ├── edge_plane.h
│ │ │ ├── edge_se3_calib.cpp
│ │ │ ├── edge_se3_calib.h
│ │ │ ├── edge_se3_euler.cpp
│ │ │ ├── edge_se3_euler.h
│ │ │ ├── edge_se3_line.cpp
│ │ │ ├── edge_se3_line.h
│ │ │ ├── edge_se3_plane_calib.cpp
│ │ │ ├── edge_se3_plane_calib.h
│ │ │ ├── g2o_types_slam3d_addons_api.h
│ │ │ ├── line3d.cpp
│ │ │ ├── line3d.h
│ │ │ ├── plane3d.h
│ │ │ ├── types_slam3d_addons.cpp
│ │ │ ├── types_slam3d_addons.h
│ │ │ ├── vertex_line3d.cpp
│ │ │ ├── vertex_line3d.h
│ │ │ ├── vertex_plane.cpp
│ │ │ ├── vertex_plane.h
│ │ │ ├── vertex_se3_euler.cpp
│ │ │ └── vertex_se3_euler.h
│ │ └── what_is_in_these_directories.txt
│ ├── script/
│ │ ├── android.toolchain.cmake
│ │ ├── install-additional-deps-windows.bat
│ │ ├── install-deps-linux.sh
│ │ ├── install-deps-osx.sh
│ │ └── install-deps-windows.bat
│ └── unit_test/
│ ├── CMakeLists.txt
│ ├── data/
│ │ ├── CMakeLists.txt
│ │ ├── data_queue_tests.cpp
│ │ └── io_data.cpp
│ ├── general/
│ │ ├── CMakeLists.txt
│ │ ├── allocate_optimizer.cpp
│ │ ├── allocate_optimizer.h
│ │ ├── auto_diff.cpp
│ │ ├── base_fixed_sized_edge.cpp
│ │ ├── batch_statistics.cpp
│ │ ├── clear_and_redo.cpp
│ │ ├── graph_operations.cpp
│ │ ├── robust_kernel_tests.cpp
│ │ └── sparse_block_matrix.cpp
│ ├── sba/
│ │ ├── CMakeLists.txt
│ │ ├── io_sba.cpp
│ │ └── io_six_dof_expmap.cpp
│ ├── sclam2d/
│ │ ├── CMakeLists.txt
│ │ ├── io_sclam2d.cpp
│ │ └── odom_convert_sclam2d.cpp
│ ├── sim3/
│ │ ├── CMakeLists.txt
│ │ ├── allocate_sim3.cpp
│ │ ├── io_sim3.cpp
│ │ └── jacobians_sim3.cpp
│ ├── slam2d/
│ │ ├── CMakeLists.txt
│ │ ├── io_slam2d.cpp
│ │ ├── jacobians_slam2d.cpp
│ │ └── mappings_se2.cpp
│ ├── slam2d_addons/
│ │ ├── CMakeLists.txt
│ │ └── io_slam2d_addons.cpp
│ ├── slam3d/
│ │ ├── CMakeLists.txt
│ │ ├── io_slam3d.cpp
│ │ ├── jacobians_slam3d.cpp
│ │ ├── mappings_slam3d.cpp
│ │ ├── optimization_slam3d.cpp
│ │ └── orthogonal_matrix.cpp
│ ├── slam3d_addons/
│ │ ├── CMakeLists.txt
│ │ └── io_slam3d_addons.cpp
│ ├── solver/
│ │ ├── CMakeLists.txt
│ │ ├── allocate_algorithm_test.cpp
│ │ ├── linear_solver_test.cpp
│ │ ├── sparse_system_helper.cpp
│ │ └── sparse_system_helper.h
│ ├── stuff/
│ │ ├── CMakeLists.txt
│ │ ├── command_args_tests.cpp
│ │ ├── filesys_tools_tests.cpp
│ │ ├── misc_tests.cpp
│ │ ├── property_tests.cpp
│ │ ├── string_tools_tests.cpp
│ │ ├── tuple_tools_tests.cpp
│ │ └── unscented_tests.cpp
│ └── test_helper/
│ ├── eigen_matcher.h
│ ├── evaluate_jacobian.h
│ ├── io.h
│ ├── random_state.h
│ └── test_main.cpp
├── build.sh
├── cmake_modules/
│ └── FindEigen3.cmake
├── include/
│ ├── Converter.h
│ ├── Frame.h
│ ├── FrameDrawer.h
│ ├── Initializer.h
│ ├── KeyFrame.h
│ ├── KeyFrameDatabase.h
│ ├── LocalMapping.h
│ ├── LoopClosing.h
│ ├── Map.h
│ ├── MapDrawer.h
│ ├── MapPoint.h
│ ├── ORBVocabulary.h
│ ├── ORBextractor.h
│ ├── ORBmatcher.h
│ ├── Optimizer.h
│ ├── PnPsolver.h
│ ├── Sim3Solver.h
│ ├── System.h
│ ├── Tracking.h
│ ├── Viewer.h
│ ├── cuda/
│ │ ├── orb_gpu.hpp
│ │ ├── orb_matcher.hpp
│ │ ├── synced_mem_holder.hpp
│ │ └── tracking_gpu.hpp
│ ├── tictoc.hpp
│ └── tictoc_cuda.hpp
└── src/
├── Converter.cpp
├── Frame.cpp
├── FrameDrawer.cpp
├── Initializer.cpp
├── KeyFrame.cpp
├── KeyFrameDatabase.cpp
├── LocalMapping.cpp
├── LoopClosing.cpp
├── Map.cpp
├── MapDrawer.cpp
├── MapPoint.cpp
├── ORBextractor.cpp
├── ORBmatcher.cpp
├── Optimizer.cpp
├── PnPsolver.cpp
├── Sim3Solver.cpp
├── System.cpp
├── Tracking.cpp
├── Viewer.cpp
└── cuda/
├── orb_FAST_apply_NMS_G.cu
├── orb_FAST_apply_NMS_L.cu
├── orb_FAST_apply_NMS_MS.cpp
├── orb_FAST_apply_NMS_MS.cu
├── orb_FAST_compute_score.cu
├── orb_FAST_obtain_keypoints.cpp
├── orb_FAST_orientation.cu
├── orb_bitpattern.cpp
├── orb_copy_output.cu
├── orb_descriptor.cu
├── orb_gaussian.cu
├── orb_gpu.cpp
├── orb_matcher.cu
├── orb_pyramid.cu
├── orb_stereo_match.cu
├── synced_mem_holder.cpp
└── tracking_isinfrustum.cu
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
build
*.*~
================================================
FILE: CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
project(Jetson-SLAM)
IF(NOT CMAKE_BUILD_TYPE)
SET(CMAKE_BUILD_TYPE Release)
ENDIF()
MESSAGE("Build type: " ${CMAKE_BUILD_TYPE})
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-error -Wno-sign-compare -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-error -Wno-sign-compare -O3 -march=native")
# Check C++11 or C++0x support
include(CheckCXXCompilerFlag)
#CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
#CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
#CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
#if(COMPILER_SUPPORTS_CXX14)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
#add_definitions(-DCOMPILEDWITHC14)
message(STATUS "Using flag -std=c++14.")
#elseif(COMPILER_SUPPORTS_CXX11)
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
# add_definitions(-DCOMPILEDWITHC11)
# message(STATUS "Using flag -std=c++11.")
#elseif(COMPILER_SUPPORTS_CXX0X)
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
# add_definitions(-DCOMPILEDWITHC0X)
# message(STATUS "Using flag -std=c++0x.")
#else()
# message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
#endif()
message(STATUS "${CMAKE_CXX_FLAGS}")
find_package(CUDA REQUIRED)
set(CUDA_NVCC_FLAGS "--std c++14")
LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
find_package(OpenCV 4 REQUIRED)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV >= 4 not found.")
endif()
find_package(Eigen3 3.1.0 REQUIRED)
find_package(Pangolin REQUIRED)
include_directories(
${PROJECT_SOURCE_DIR}
${PROJECT_SOURCE_DIR}/include
${EIGEN3_INCLUDE_DIR}
${PROJECT_SOURCE_DIR}/Thirdparty/
${PROJECT_SOURCE_DIR}/Thirdparty/g2o
${Pangolin_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
)
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib)
cuda_add_library(${PROJECT_NAME} SHARED
src/Converter.cpp
src/Frame.cpp
src/FrameDrawer.cpp
src/Initializer.cpp
src/KeyFrame.cpp
src/KeyFrameDatabase.cpp
src/LocalMapping.cpp
src/LoopClosing.cpp
src/Map.cpp
src/MapDrawer.cpp
src/MapPoint.cpp
src/Optimizer.cpp
src/ORBextractor.cpp
src/ORBmatcher.cpp
src/PnPsolver.cpp
src/Sim3Solver.cpp
src/System.cpp
src/Tracking.cpp
src/Viewer.cpp
src/cuda/orb_bitpattern.cpp
src/cuda/orb_copy_output.cu
src/cuda/orb_descriptor.cu
src/cuda/orb_FAST_apply_NMS_G.cu
src/cuda/orb_FAST_apply_NMS_L.cu
src/cuda/orb_FAST_apply_NMS_MS.cpp
src/cuda/orb_FAST_apply_NMS_MS.cu
src/cuda/orb_FAST_compute_score.cu
src/cuda/orb_FAST_obtain_keypoints.cpp
src/cuda/orb_FAST_orientation.cu
src/cuda/orb_gaussian.cu
src/cuda/orb_gpu.cpp
src/cuda/orb_matcher.cu
src/cuda/orb_pyramid.cu
src/cuda/orb_stereo_match.cu
src/cuda/synced_mem_holder.cpp
src/cuda/tracking_isinfrustum.cu
)
target_link_libraries(${PROJECT_NAME}
${OpenCV_LIBS}
${EIGEN3_LIBS}
${Pangolin_LIBRARIES}
${CUDA_LIBRARIES}
${CUDA_CUBLAS_LIBRARIES}
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
)
# Build execs
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Stereo)
add_executable(stereo_kitti Examples/Stereo/stereo_kitti.cpp)
target_link_libraries(stereo_kitti ${PROJECT_NAME})
add_executable(stereo_euroc Examples/Stereo/stereo_euroc.cpp)
target_link_libraries(stereo_euroc ${PROJECT_NAME})
add_executable(stereo_live Examples/Stereo/stereo_live.cpp)
target_link_libraries(stereo_live ${PROJECT_NAME})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/RGB-D)
add_executable(rgbd_tum
Examples/RGB-D/rgbd_tum.cpp)
target_link_libraries(rgbd_tum ${PROJECT_NAME})
add_executable(rgbd_live
Examples/RGB-D/rgbd_live.cpp)
target_link_libraries(rgbd_live ${PROJECT_NAME})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Monocular)
add_executable(mono_live
Examples/Monocular/mono_live.cpp)
target_link_libraries(mono_live ${PROJECT_NAME})
add_executable(mono_tum
Examples/Monocular/mono_tum.cpp)
target_link_libraries(mono_tum ${PROJECT_NAME})
add_executable(mono_kitti
Examples/Monocular/mono_kitti.cpp)
target_link_libraries(mono_kitti ${PROJECT_NAME})
add_executable(mono_euroc
Examples/Monocular/mono_euroc.cpp)
target_link_libraries(mono_euroc ${PROJECT_NAME})
================================================
FILE: Examples/Monocular/EuRoC.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 458.654
Camera.fy: 457.296
Camera.cx: 367.215
Camera.cy: 248.375
Camera.k1: -0.28340811
Camera.k2: 0.07395907
Camera.p1: 0.00019359
Camera.p2: 1.76187114e-05
# Camera frames per second
Camera.fps: 20.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#---------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/MH01.txt
================================================
1403636579763555584
1403636579813555456
1403636579863555584
1403636579913555456
1403636579963555584
1403636580013555456
1403636580063555584
1403636580113555456
1403636580163555584
1403636580213555456
1403636580263555584
1403636580313555456
1403636580363555584
1403636580413555456
1403636580463555584
1403636580513555456
1403636580563555584
1403636580613555456
1403636580663555584
1403636580713555456
1403636580763555584
1403636580813555456
1403636580863555584
1403636580913555456
1403636580963555584
1403636581013555456
1403636581063555584
1403636581113555456
1403636581163555584
1403636581213555456
1403636581263555584
1403636581313555456
1403636581363555584
1403636581413555456
1403636581463555584
1403636581513555456
1403636581563555584
1403636581613555456
1403636581663555584
1403636581713555456
1403636581763555584
1403636581813555456
1403636581863555584
1403636581913555456
1403636581963555584
1403636582013555456
1403636582063555584
1403636582113555456
1403636582163555584
1403636582213555456
1403636582263555584
1403636582313555456
1403636582363555584
1403636582413555456
1403636582463555584
1403636582513555456
1403636582563555584
1403636582613555456
1403636582663555584
1403636582713555456
1403636582763555584
1403636582813555456
1403636582863555584
1403636582913555456
1403636582963555584
1403636583013555456
1403636583063555584
1403636583113555456
1403636583163555584
1403636583213555456
1403636583263555584
1403636583313555456
1403636583363555584
1403636583413555456
1403636583463555584
1403636583513555456
1403636583563555584
1403636583613555456
1403636583663555584
1403636583713555456
1403636583763555584
1403636583813555456
1403636583863555584
1403636583913555456
1403636583963555584
1403636584013555456
1403636584063555584
1403636584113555456
1403636584163555584
1403636584213555456
1403636584263555584
1403636584313555456
1403636584363555584
1403636584413555456
1403636584463555584
1403636584513555456
1403636584563555584
1403636584613555456
1403636584663555584
1403636584713555456
1403636584763555584
1403636584813555456
1403636584863555584
1403636584913555456
1403636584963555584
1403636585013555456
1403636585063555584
1403636585113555456
1403636585163555584
1403636585213555456
1403636585263555584
1403636585313555456
1403636585363555584
1403636585413555456
1403636585463555584
1403636585513555456
1403636585563555584
1403636585613555456
1403636585663555584
1403636585713555456
1403636585763555584
1403636585813555456
1403636585863555584
1403636585913555456
1403636585963555584
1403636586013555456
1403636586063555584
1403636586113555456
1403636586163555584
1403636586213555456
1403636586263555584
1403636586313555456
1403636586363555584
1403636586413555456
1403636586463555584
1403636586513555456
1403636586563555584
1403636586613555456
1403636586663555584
1403636586713555456
1403636586763555584
1403636586813555456
1403636586863555584
1403636586913555456
1403636586963555584
1403636587013555456
1403636587063555584
1403636587113555456
1403636587163555584
1403636587213555456
1403636587263555584
1403636587313555456
1403636587363555584
1403636587413555456
1403636587463555584
1403636587513555456
1403636587563555584
1403636587613555456
1403636587663555584
1403636587713555456
1403636587763555584
1403636587813555456
1403636587863555584
1403636587913555456
1403636587963555584
1403636588013555456
1403636588063555584
1403636588113555456
1403636588163555584
1403636588213555456
1403636588263555584
1403636588313555456
1403636588363555584
1403636588413555456
1403636588463555584
1403636588513555456
1403636588563555584
1403636588613555456
1403636588663555584
1403636588713555456
1403636588763555584
1403636588813555456
1403636588863555584
1403636588913555456
1403636588963555584
1403636589013555456
1403636589063555584
1403636589113555456
1403636589163555584
1403636589213555456
1403636589263555584
1403636589313555456
1403636589363555584
1403636589413555456
1403636589463555584
1403636589513555456
1403636589563555584
1403636589613555456
1403636589663555584
1403636589713555456
1403636589763555584
1403636589813555456
1403636589863555584
1403636589913555456
1403636589963555584
1403636590013555456
1403636590063555584
1403636590113555456
1403636590163555584
1403636590213555456
1403636590263555584
1403636590313555456
1403636590363555584
1403636590413555456
1403636590463555584
1403636590513555456
1403636590563555584
1403636590613555456
1403636590663555584
1403636590713555456
1403636590763555584
1403636590813555456
1403636590863555584
1403636590913555456
1403636590963555584
1403636591013555456
1403636591063555584
1403636591113555456
1403636591163555584
1403636591213555456
1403636591263555584
1403636591313555456
1403636591363555584
1403636591413555456
1403636591463555584
1403636591513555456
1403636591563555584
1403636591613555456
1403636591663555584
1403636591713555456
1403636591763555584
1403636591813555456
1403636591863555584
1403636591913555456
1403636591963555584
1403636592013555456
1403636592063555584
1403636592113555456
1403636592163555584
1403636592213555456
1403636592263555584
1403636592313555456
1403636592363555584
1403636592413555456
1403636592463555584
1403636592513555456
1403636592563555584
1403636592613555456
1403636592663555584
1403636592713555456
1403636592763555584
1403636592813555456
1403636592863555584
1403636592913555456
1403636592963555584
1403636593013555456
1403636593063555584
1403636593113555456
1403636593163555584
1403636593213555456
1403636593263555584
1403636593313555456
1403636593363555584
1403636593413555456
1403636593463555584
1403636593513555456
1403636593563555584
1403636593613555456
1403636593663555584
1403636593713555456
1403636593763555584
1403636593813555456
1403636593863555584
1403636593913555456
1403636593963555584
1403636594013555456
1403636594063555584
1403636594113555456
1403636594163555584
1403636594213555456
1403636594263555584
1403636594313555456
1403636594363555584
1403636594413555456
1403636594463555584
1403636594513555456
1403636594563555584
1403636594613555456
1403636594663555584
1403636594713555456
1403636594763555584
1403636594813555456
1403636594863555584
1403636594913555456
1403636594963555584
1403636595013555456
1403636595063555584
1403636595113555456
1403636595163555584
1403636595213555456
1403636595263555584
1403636595313555456
1403636595363555584
1403636595413555456
1403636595463555584
1403636595513555456
1403636595563555584
1403636595613555456
1403636595663555584
1403636595713555456
1403636595763555584
1403636595813555456
1403636595863555584
1403636595913555456
1403636595963555584
1403636596013555456
1403636596063555584
1403636596113555456
1403636596163555584
1403636596213555456
1403636596263555584
1403636596313555456
1403636596363555584
1403636596413555456
1403636596463555584
1403636596513555456
1403636596563555584
1403636596613555456
1403636596663555584
1403636596713555456
1403636596763555584
1403636596813555456
1403636596863555584
1403636596913555456
1403636596963555584
1403636597013555456
1403636597063555584
1403636597113555456
1403636597163555584
1403636597213555456
1403636597263555584
1403636597313555456
1403636597363555584
1403636597413555456
1403636597463555584
1403636597513555456
1403636597563555584
1403636597613555456
1403636597663555584
1403636597713555456
1403636597763555584
1403636597813555456
1403636597863555584
1403636597913555456
1403636597963555584
1403636598013555456
1403636598063555584
1403636598113555456
1403636598163555584
1403636598213555456
1403636598263555584
1403636598313555456
1403636598363555584
1403636598413555456
1403636598463555584
1403636598513555456
1403636598563555584
1403636598613555456
1403636598663555584
1403636598713555456
1403636598763555584
1403636598813555456
1403636598863555584
1403636598913555456
1403636598963555584
1403636599013555456
1403636599063555584
1403636599113555456
1403636599163555584
1403636599213555456
1403636599263555584
1403636599313555456
1403636599363555584
1403636599413555456
1403636599463555584
1403636599513555456
1403636599563555584
1403636599613555456
1403636599663555584
1403636599713555456
1403636599763555584
1403636599813555456
1403636599863555584
1403636599913555456
1403636599963555584
1403636600013555456
1403636600063555584
1403636600113555456
1403636600163555584
1403636600213555456
1403636600263555584
1403636600313555456
1403636600363555584
1403636600413555456
1403636600463555584
1403636600513555456
1403636600563555584
1403636600613555456
1403636600663555584
1403636600713555456
1403636600763555584
1403636600813555456
1403636600863555584
1403636600913555456
1403636600963555584
1403636601013555456
1403636601063555584
1403636601113555456
1403636601163555584
1403636601213555456
1403636601263555584
1403636601313555456
1403636601363555584
1403636601413555456
1403636601463555584
1403636601513555456
1403636601563555584
1403636601613555456
1403636601663555584
1403636601713555456
1403636601763555584
1403636601813555456
1403636601863555584
1403636601913555456
1403636601963555584
1403636602013555456
1403636602063555584
1403636602113555456
1403636602163555584
1403636602213555456
1403636602263555584
1403636602313555456
1403636602363555584
1403636602413555456
1403636602463555584
1403636602513555456
1403636602563555584
1403636602613555456
1403636602663555584
1403636602713555456
1403636602763555584
1403636602813555456
1403636602863555584
1403636602913555456
1403636602963555584
1403636603013555456
1403636603063555584
1403636603113555456
1403636603163555584
1403636603213555456
1403636603263555584
1403636603313555456
1403636603363555584
1403636603413555456
1403636603463555584
1403636603513555456
1403636603563555584
1403636603613555456
1403636603663555584
1403636603713555456
1403636603763555584
1403636603813555456
1403636603863555584
1403636603913555456
1403636603963555584
1403636604013555456
1403636604063555584
1403636604113555456
1403636604163555584
1403636604213555456
1403636604263555584
1403636604313555456
1403636604363555584
1403636604413555456
1403636604463555584
1403636604513555456
1403636604563555584
1403636604613555456
1403636604663555584
1403636604713555456
1403636604763555584
1403636604813555456
1403636604863555584
1403636604913555456
1403636604963555584
1403636605013555456
1403636605063555584
1403636605113555456
1403636605163555584
1403636605213555456
1403636605263555584
1403636605313555456
1403636605363555584
1403636605413555456
1403636605463555584
1403636605513555456
1403636605563555584
1403636605613555456
1403636605663555584
1403636605713555456
1403636605763555584
1403636605813555456
1403636605863555584
1403636605913555456
1403636605963555584
1403636606013555456
1403636606063555584
1403636606113555456
1403636606163555584
1403636606213555456
1403636606263555584
1403636606313555456
1403636606363555584
1403636606413555456
1403636606463555584
1403636606513555456
1403636606563555584
1403636606613555456
1403636606663555584
1403636606713555456
1403636606763555584
1403636606813555456
1403636606863555584
1403636606913555456
1403636606963555584
1403636607013555456
1403636607063555584
1403636607113555456
1403636607163555584
1403636607213555456
1403636607263555584
1403636607313555456
1403636607363555584
1403636607413555456
1403636607463555584
1403636607513555456
1403636607563555584
1403636607613555456
1403636607663555584
1403636607713555456
1403636607763555584
1403636607813555456
1403636607863555584
1403636607913555456
1403636607963555584
1403636608013555456
1403636608063555584
1403636608113555456
1403636608163555584
1403636608213555456
1403636608263555584
1403636608313555456
1403636608363555584
1403636608413555456
1403636608463555584
1403636608513555456
1403636608563555584
1403636608613555456
1403636608663555584
1403636608713555456
1403636608763555584
1403636608813555456
1403636608863555584
1403636608913555456
1403636608963555584
1403636609013555456
1403636609063555584
1403636609113555456
1403636609163555584
1403636609213555456
1403636609263555584
1403636609313555456
1403636609363555584
1403636609413555456
1403636609463555584
1403636609513555456
1403636609563555584
1403636609613555456
1403636609663555584
1403636609713555456
1403636609763555584
1403636609813555456
1403636609863555584
1403636609913555456
1403636609963555584
1403636610013555456
1403636610063555584
1403636610113555456
1403636610163555584
1403636610213555456
1403636610263555584
1403636610313555456
1403636610363555584
1403636610413555456
1403636610463555584
1403636610513555456
1403636610563555584
1403636610613555456
1403636610663555584
1403636610713555456
1403636610763555584
1403636610813555456
1403636610863555584
1403636610913555456
1403636610963555584
1403636611013555456
1403636611063555584
1403636611113555456
1403636611163555584
1403636611213555456
1403636611263555584
1403636611313555456
1403636611363555584
1403636611413555456
1403636611463555584
1403636611513555456
1403636611563555584
1403636611613555456
1403636611663555584
1403636611713555456
1403636611763555584
1403636611813555456
1403636611863555584
1403636611913555456
1403636611963555584
1403636612013555456
1403636612063555584
1403636612113555456
1403636612163555584
1403636612213555456
1403636612263555584
1403636612313555456
1403636612363555584
1403636612413555456
1403636612463555584
1403636612513555456
1403636612563555584
1403636612613555456
1403636612663555584
1403636612713555456
1403636612763555584
1403636612813555456
1403636612863555584
1403636612913555456
1403636612963555584
1403636613013555456
1403636613063555584
1403636613113555456
1403636613163555584
1403636613213555456
1403636613263555584
1403636613313555456
1403636613363555584
1403636613413555456
1403636613463555584
1403636613513555456
1403636613563555584
1403636613613555456
1403636613663555584
1403636613713555456
1403636613763555584
1403636613813555456
1403636613863555584
1403636613913555456
1403636613963555584
1403636614013555456
1403636614063555584
1403636614113555456
1403636614163555584
1403636614213555456
1403636614263555584
1403636614313555456
1403636614363555584
1403636614413555456
1403636614463555584
1403636614513555456
1403636614563555584
1403636614613555456
1403636614663555584
1403636614713555456
1403636614763555584
1403636614813555456
1403636614863555584
1403636614913555456
1403636614963555584
1403636615013555456
1403636615063555584
1403636615113555456
1403636615163555584
1403636615213555456
1403636615263555584
1403636615313555456
1403636615363555584
1403636615413555456
1403636615463555584
1403636615513555456
1403636615563555584
1403636615613555456
1403636615663555584
1403636615713555456
1403636615763555584
1403636615813555456
1403636615863555584
1403636615913555456
1403636615963555584
1403636616013555456
1403636616063555584
1403636616113555456
1403636616163555584
1403636616213555456
1403636616263555584
1403636616313555456
1403636616363555584
1403636616413555456
1403636616463555584
1403636616513555456
1403636616563555584
1403636616613555456
1403636616663555584
1403636616713555456
1403636616763555584
1403636616813555456
1403636616863555584
1403636616913555456
1403636616963555584
1403636617013555456
1403636617063555584
1403636617113555456
1403636617163555584
1403636617213555456
1403636617263555584
1403636617313555456
1403636617363555584
1403636617413555456
1403636617463555584
1403636617513555456
1403636617563555584
1403636617613555456
1403636617663555584
1403636617713555456
1403636617763555584
1403636617813555456
1403636617863555584
1403636617913555456
1403636617963555584
1403636618013555456
1403636618063555584
1403636618113555456
1403636618163555584
1403636618213555456
1403636618263555584
1403636618313555456
1403636618363555584
1403636618413555456
1403636618463555584
1403636618513555456
1403636618563555584
1403636618613555456
1403636618663555584
1403636618713555456
1403636618763555584
1403636618813555456
1403636618863555584
1403636618913555456
1403636618963555584
1403636619013555456
1403636619063555584
1403636619113555456
1403636619163555584
1403636619213555456
1403636619263555584
1403636619313555456
1403636619363555584
1403636619413555456
1403636619463555584
1403636619513555456
1403636619563555584
1403636619613555456
1403636619663555584
1403636619713555456
1403636619763555584
1403636619813555456
1403636619863555584
1403636619913555456
1403636619963555584
1403636620013555456
1403636620063555584
1403636620113555456
1403636620163555584
1403636620213555456
1403636620263555584
1403636620313555456
1403636620363555584
1403636620413555456
1403636620463555584
1403636620513555456
1403636620563555584
1403636620613555456
1403636620663555584
1403636620713555456
1403636620763555584
1403636620813555456
1403636620863555584
1403636620913555456
1403636620963555584
1403636621013555456
1403636621063555584
1403636621113555456
1403636621163555584
1403636621213555456
1403636621263555584
1403636621313555456
1403636621363555584
1403636621413555456
1403636621463555584
1403636621513555456
1403636621563555584
1403636621613555456
1403636621663555584
1403636621713555456
1403636621763555584
1403636621813555456
1403636621863555584
1403636621913555456
1403636621963555584
1403636622013555456
1403636622063555584
1403636622113555456
1403636622163555584
1403636622213555456
1403636622263555584
1403636622313555456
1403636622363555584
1403636622413555456
1403636622463555584
1403636622513555456
1403636622563555584
1403636622613555456
1403636622663555584
1403636622713555456
1403636622763555584
1403636622813555456
1403636622863555584
1403636622913555456
1403636622963555584
1403636623013555456
1403636623063555584
1403636623113555456
1403636623163555584
1403636623213555456
1403636623263555584
1403636623313555456
1403636623363555584
1403636623413555456
1403636623463555584
1403636623513555456
1403636623563555584
1403636623613555456
1403636623663555584
1403636623713555456
1403636623763555584
1403636623813555456
1403636623863555584
1403636623913555456
1403636623963555584
1403636624013555456
1403636624063555584
1403636624113555456
1403636624163555584
1403636624213555456
1403636624263555584
1403636624313555456
1403636624363555584
1403636624413555456
1403636624463555584
1403636624513555456
1403636624563555584
1403636624613555456
1403636624663555584
1403636624713555456
1403636624763555584
1403636624813555456
1403636624863555584
1403636624913555456
1403636624963555584
1403636625013555456
1403636625063555584
1403636625113555456
1403636625163555584
1403636625213555456
1403636625263555584
1403636625313555456
1403636625363555584
1403636625413555456
1403636625463555584
1403636625513555456
1403636625563555584
1403636625613555456
1403636625663555584
1403636625713555456
1403636625763555584
1403636625813555456
1403636625863555584
1403636625913555456
1403636625963555584
1403636626013555456
1403636626063555584
1403636626113555456
1403636626163555584
1403636626213555456
1403636626263555584
1403636626313555456
1403636626363555584
1403636626413555456
1403636626463555584
1403636626513555456
1403636626563555584
1403636626613555456
1403636626663555584
1403636626713555456
1403636626763555584
1403636626813555456
1403636626863555584
1403636626913555456
1403636626963555584
1403636627013555456
1403636627063555584
1403636627113555456
1403636627163555584
1403636627213555456
1403636627263555584
1403636627313555456
1403636627363555584
1403636627413555456
1403636627463555584
1403636627513555456
1403636627563555584
1403636627613555456
1403636627663555584
1403636627713555456
1403636627763555584
1403636627813555456
1403636627863555584
1403636627913555456
1403636627963555584
1403636628013555456
1403636628063555584
1403636628113555456
1403636628163555584
1403636628213555456
1403636628263555584
1403636628313555456
1403636628363555584
1403636628413555456
1403636628463555584
1403636628513555456
1403636628563555584
1403636628613555456
1403636628663555584
1403636628713555456
1403636628763555584
1403636628813555456
1403636628863555584
1403636628913555456
1403636628963555584
1403636629013555456
1403636629063555584
1403636629113555456
1403636629163555584
1403636629213555456
1403636629263555584
1403636629313555456
1403636629363555584
1403636629413555456
1403636629463555584
1403636629513555456
1403636629563555584
1403636629613555456
1403636629663555584
1403636629713555456
1403636629763555584
1403636629813555456
1403636629863555584
1403636629913555456
1403636629963555584
1403636630013555456
1403636630063555584
1403636630113555456
1403636630163555584
1403636630213555456
1403636630263555584
1403636630313555456
1403636630363555584
1403636630413555456
1403636630463555584
1403636630513555456
1403636630563555584
1403636630613555456
1403636630663555584
1403636630713555456
1403636630763555584
1403636630813555456
1403636630863555584
1403636630913555456
1403636630963555584
1403636631013555456
1403636631063555584
1403636631113555456
1403636631163555584
1403636631213555456
1403636631263555584
1403636631313555456
1403636631363555584
1403636631413555456
1403636631463555584
1403636631513555456
1403636631563555584
1403636631613555456
1403636631663555584
1403636631713555456
1403636631763555584
1403636631813555456
1403636631863555584
1403636631913555456
1403636631963555584
1403636632013555456
1403636632063555584
1403636632113555456
1403636632163555584
1403636632213555456
1403636632263555584
1403636632313555456
1403636632363555584
1403636632413555456
1403636632463555584
1403636632513555456
1403636632563555584
1403636632613555456
1403636632663555584
1403636632713555456
1403636632763555584
1403636632813555456
1403636632863555584
1403636632913555456
1403636632963555584
1403636633013555456
1403636633063555584
1403636633113555456
1403636633163555584
1403636633213555456
1403636633263555584
1403636633313555456
1403636633363555584
1403636633413555456
1403636633463555584
1403636633513555456
1403636633563555584
1403636633613555456
1403636633663555584
1403636633713555456
1403636633763555584
1403636633813555456
1403636633863555584
1403636633913555456
1403636633963555584
1403636634013555456
1403636634063555584
1403636634113555456
1403636634163555584
1403636634213555456
1403636634263555584
1403636634313555456
1403636634363555584
1403636634413555456
1403636634463555584
1403636634513555456
1403636634563555584
1403636634613555456
1403636634663555584
1403636634713555456
1403636634763555584
1403636634813555456
1403636634863555584
1403636634913555456
1403636634963555584
1403636635013555456
1403636635063555584
1403636635113555456
1403636635163555584
1403636635213555456
1403636635263555584
1403636635313555456
1403636635363555584
1403636635413555456
1403636635463555584
1403636635513555456
1403636635563555584
1403636635613555456
1403636635663555584
1403636635713555456
1403636635763555584
1403636635813555456
1403636635863555584
1403636635913555456
1403636635963555584
1403636636013555456
1403636636063555584
1403636636113555456
1403636636163555584
1403636636213555456
1403636636263555584
1403636636313555456
1403636636363555584
1403636636413555456
1403636636463555584
1403636636513555456
1403636636563555584
1403636636613555456
1403636636663555584
1403636636713555456
1403636636763555584
1403636636813555456
1403636636863555584
1403636636913555456
1403636636963555584
1403636637013555456
1403636637063555584
1403636637113555456
1403636637163555584
1403636637213555456
1403636637263555584
1403636637313555456
1403636637363555584
1403636637413555456
1403636637463555584
1403636637513555456
1403636637563555584
1403636637613555456
1403636637663555584
1403636637713555456
1403636637763555584
1403636637813555456
1403636637863555584
1403636637913555456
1403636637963555584
1403636638013555456
1403636638063555584
1403636638113555456
1403636638163555584
1403636638213555456
1403636638263555584
1403636638313555456
1403636638363555584
1403636638413555456
1403636638463555584
1403636638513555456
1403636638563555584
1403636638613555456
1403636638663555584
1403636638713555456
1403636638763555584
1403636638813555456
1403636638863555584
1403636638913555456
1403636638963555584
1403636639013555456
1403636639063555584
1403636639113555456
1403636639163555584
1403636639213555456
1403636639263555584
1403636639313555456
1403636639363555584
1403636639413555456
1403636639463555584
1403636639513555456
1403636639563555584
1403636639613555456
1403636639663555584
1403636639713555456
1403636639763555584
1403636639813555456
1403636639863555584
1403636639913555456
1403636639963555584
1403636640013555456
1403636640063555584
1403636640113555456
1403636640163555584
1403636640213555456
1403636640263555584
1403636640313555456
1403636640363555584
1403636640413555456
1403636640463555584
1403636640513555456
1403636640563555584
1403636640613555456
1403636640663555584
1403636640713555456
1403636640763555584
1403636640813555456
1403636640863555584
1403636640913555456
1403636640963555584
1403636641013555456
1403636641063555584
1403636641113555456
1403636641163555584
1403636641213555456
1403636641263555584
1403636641313555456
1403636641363555584
1403636641413555456
1403636641463555584
1403636641513555456
1403636641563555584
1403636641613555456
1403636641663555584
1403636641713555456
1403636641763555584
1403636641813555456
1403636641863555584
1403636641913555456
1403636641963555584
1403636642013555456
1403636642063555584
1403636642113555456
1403636642163555584
1403636642213555456
1403636642263555584
1403636642313555456
1403636642363555584
1403636642413555456
1403636642463555584
1403636642513555456
1403636642563555584
1403636642613555456
1403636642663555584
1403636642713555456
1403636642763555584
1403636642813555456
1403636642863555584
1403636642913555456
1403636642963555584
1403636643013555456
1403636643063555584
1403636643113555456
1403636643163555584
1403636643213555456
1403636643263555584
1403636643313555456
1403636643363555584
1403636643413555456
1403636643463555584
1403636643513555456
1403636643563555584
1403636643613555456
1403636643663555584
1403636643713555456
1403636643763555584
1403636643813555456
1403636643863555584
1403636643913555456
1403636643963555584
1403636644013555456
1403636644063555584
1403636644113555456
1403636644163555584
1403636644213555456
1403636644263555584
1403636644313555456
1403636644363555584
1403636644413555456
1403636644463555584
1403636644513555456
1403636644563555584
1403636644613555456
1403636644663555584
1403636644713555456
1403636644763555584
1403636644813555456
1403636644863555584
1403636644913555456
1403636644963555584
1403636645013555456
1403636645063555584
1403636645113555456
1403636645163555584
1403636645213555456
1403636645263555584
1403636645313555456
1403636645363555584
1403636645413555456
1403636645463555584
1403636645513555456
1403636645563555584
1403636645613555456
1403636645663555584
1403636645713555456
1403636645763555584
1403636645813555456
1403636645863555584
1403636645913555456
1403636645963555584
1403636646013555456
1403636646063555584
1403636646113555456
1403636646163555584
1403636646213555456
1403636646263555584
1403636646313555456
1403636646363555584
1403636646413555456
1403636646463555584
1403636646513555456
1403636646563555584
1403636646613555456
1403636646663555584
1403636646713555456
1403636646763555584
1403636646813555456
1403636646863555584
1403636646913555456
1403636646963555584
1403636647013555456
1403636647063555584
1403636647113555456
1403636647163555584
1403636647213555456
1403636647263555584
1403636647313555456
1403636647363555584
1403636647413555456
1403636647463555584
1403636647513555456
1403636647563555584
1403636647613555456
1403636647663555584
1403636647713555456
1403636647763555584
1403636647813555456
1403636647863555584
1403636647913555456
1403636647963555584
1403636648013555456
1403636648063555584
1403636648113555456
1403636648163555584
1403636648213555456
1403636648263555584
1403636648313555456
1403636648363555584
1403636648413555456
1403636648463555584
1403636648513555456
1403636648563555584
1403636648613555456
1403636648663555584
1403636648713555456
1403636648763555584
1403636648813555456
1403636648863555584
1403636648913555456
1403636648963555584
1403636649013555456
1403636649063555584
1403636649113555456
1403636649163555584
1403636649213555456
1403636649263555584
1403636649313555456
1403636649363555584
1403636649413555456
1403636649463555584
1403636649513555456
1403636649563555584
1403636649613555456
1403636649663555584
1403636649713555456
1403636649763555584
1403636649813555456
1403636649863555584
1403636649913555456
1403636649963555584
1403636650013555456
1403636650063555584
1403636650113555456
1403636650163555584
1403636650213555456
1403636650263555584
1403636650313555456
1403636650363555584
1403636650413555456
1403636650463555584
1403636650513555456
1403636650563555584
1403636650613555456
1403636650663555584
1403636650713555456
1403636650763555584
1403636650813555456
1403636650863555584
1403636650913555456
1403636650963555584
1403636651013555456
1403636651063555584
1403636651113555456
1403636651163555584
1403636651213555456
1403636651263555584
1403636651313555456
1403636651363555584
1403636651413555456
1403636651463555584
1403636651513555456
1403636651563555584
1403636651613555456
1403636651663555584
1403636651713555456
1403636651763555584
1403636651813555456
1403636651863555584
1403636651913555456
1403636651963555584
1403636652013555456
1403636652063555584
1403636652113555456
1403636652163555584
1403636652213555456
1403636652263555584
1403636652313555456
1403636652363555584
1403636652413555456
1403636652463555584
1403636652513555456
1403636652563555584
1403636652613555456
1403636652663555584
1403636652713555456
1403636652763555584
1403636652813555456
1403636652863555584
1403636652913555456
1403636652963555584
1403636653013555456
1403636653063555584
1403636653113555456
1403636653163555584
1403636653213555456
1403636653263555584
1403636653313555456
1403636653363555584
1403636653413555456
1403636653463555584
1403636653513555456
1403636653563555584
1403636653613555456
1403636653663555584
1403636653713555456
1403636653763555584
1403636653813555456
1403636653863555584
1403636653913555456
1403636653963555584
1403636654013555456
1403636654063555584
1403636654113555456
1403636654163555584
1403636654213555456
1403636654263555584
1403636654313555456
1403636654363555584
1403636654413555456
1403636654463555584
1403636654513555456
1403636654563555584
1403636654613555456
1403636654663555584
1403636654713555456
1403636654763555584
1403636654813555456
1403636654863555584
1403636654913555456
1403636654963555584
1403636655013555456
1403636655063555584
1403636655113555456
1403636655163555584
1403636655213555456
1403636655263555584
1403636655313555456
1403636655363555584
1403636655413555456
1403636655463555584
1403636655513555456
1403636655563555584
1403636655613555456
1403636655663555584
1403636655713555456
1403636655763555584
1403636655813555456
1403636655863555584
1403636655913555456
1403636655963555584
1403636656013555456
1403636656063555584
1403636656113555456
1403636656163555584
1403636656213555456
1403636656263555584
1403636656313555456
1403636656363555584
1403636656413555456
1403636656463555584
1403636656513555456
1403636656563555584
1403636656613555456
1403636656663555584
1403636656713555456
1403636656763555584
1403636656813555456
1403636656863555584
1403636656913555456
1403636656963555584
1403636657013555456
1403636657063555584
1403636657113555456
1403636657163555584
1403636657213555456
1403636657263555584
1403636657313555456
1403636657363555584
1403636657413555456
1403636657463555584
1403636657513555456
1403636657563555584
1403636657613555456
1403636657663555584
1403636657713555456
1403636657763555584
1403636657813555456
1403636657863555584
1403636657913555456
1403636657963555584
1403636658013555456
1403636658063555584
1403636658113555456
1403636658163555584
1403636658213555456
1403636658263555584
1403636658313555456
1403636658363555584
1403636658413555456
1403636658463555584
1403636658513555456
1403636658563555584
1403636658613555456
1403636658663555584
1403636658713555456
1403636658763555584
1403636658813555456
1403636658863555584
1403636658913555456
1403636658963555584
1403636659013555456
1403636659063555584
1403636659113555456
1403636659163555584
1403636659213555456
1403636659263555584
1403636659313555456
1403636659363555584
1403636659413555456
1403636659463555584
1403636659513555456
1403636659563555584
1403636659613555456
1403636659663555584
1403636659713555456
1403636659763555584
1403636659813555456
1403636659863555584
1403636659913555456
1403636659963555584
1403636660013555456
1403636660063555584
1403636660113555456
1403636660163555584
1403636660213555456
1403636660263555584
1403636660313555456
1403636660363555584
1403636660413555456
1403636660463555584
1403636660513555456
1403636660563555584
1403636660613555456
1403636660663555584
1403636660713555456
1403636660763555584
1403636660813555456
1403636660863555584
1403636660913555456
1403636660963555584
1403636661013555456
1403636661063555584
1403636661113555456
1403636661163555584
1403636661213555456
1403636661263555584
1403636661313555456
1403636661363555584
1403636661413555456
1403636661463555584
1403636661513555456
1403636661563555584
1403636661613555456
1403636661663555584
1403636661713555456
1403636661763555584
1403636661813555456
1403636661863555584
1403636661913555456
1403636661963555584
1403636662013555456
1403636662063555584
1403636662113555456
1403636662163555584
1403636662213555456
1403636662263555584
1403636662313555456
1403636662363555584
1403636662413555456
1403636662463555584
1403636662513555456
1403636662563555584
1403636662613555456
1403636662663555584
1403636662713555456
1403636662763555584
1403636662813555456
1403636662863555584
1403636662913555456
1403636662963555584
1403636663013555456
1403636663063555584
1403636663113555456
1403636663163555584
1403636663213555456
1403636663263555584
1403636663313555456
1403636663363555584
1403636663413555456
1403636663463555584
1403636663513555456
1403636663563555584
1403636663613555456
1403636663663555584
1403636663713555456
1403636663763555584
1403636663813555456
1403636663863555584
1403636663913555456
1403636663963555584
1403636664013555456
1403636664063555584
1403636664113555456
1403636664163555584
1403636664213555456
1403636664263555584
1403636664313555456
1403636664363555584
1403636664413555456
1403636664463555584
1403636664513555456
1403636664563555584
1403636664613555456
1403636664663555584
1403636664713555456
1403636664763555584
1403636664813555456
1403636664863555584
1403636664913555456
1403636664963555584
1403636665013555456
1403636665063555584
1403636665113555456
1403636665163555584
1403636665213555456
1403636665263555584
1403636665313555456
1403636665363555584
1403636665413555456
1403636665463555584
1403636665513555456
1403636665563555584
1403636665613555456
1403636665663555584
1403636665713555456
1403636665763555584
1403636665813555456
1403636665863555584
1403636665913555456
1403636665963555584
1403636666013555456
1403636666063555584
1403636666113555456
1403636666163555584
1403636666213555456
1403636666263555584
1403636666313555456
1403636666363555584
1403636666413555456
1403636666463555584
1403636666513555456
1403636666563555584
1403636666613555456
1403636666663555584
1403636666713555456
1403636666763555584
1403636666813555456
1403636666863555584
1403636666913555456
1403636666963555584
1403636667013555456
1403636667063555584
1403636667113555456
1403636667163555584
1403636667213555456
1403636667263555584
1403636667313555456
1403636667363555584
1403636667413555456
1403636667463555584
1403636667513555456
1403636667563555584
1403636667613555456
1403636667663555584
1403636667713555456
1403636667763555584
1403636667813555456
1403636667863555584
1403636667913555456
1403636667963555584
1403636668013555456
1403636668063555584
1403636668113555456
1403636668163555584
1403636668213555456
1403636668263555584
1403636668313555456
1403636668363555584
1403636668413555456
1403636668463555584
1403636668513555456
1403636668563555584
1403636668613555456
1403636668663555584
1403636668713555456
1403636668763555584
1403636668813555456
1403636668863555584
1403636668913555456
1403636668963555584
1403636669013555456
1403636669063555584
1403636669113555456
1403636669163555584
1403636669213555456
1403636669263555584
1403636669313555456
1403636669363555584
1403636669413555456
1403636669463555584
1403636669513555456
1403636669563555584
1403636669613555456
1403636669663555584
1403636669713555456
1403636669763555584
1403636669813555456
1403636669863555584
1403636669913555456
1403636669963555584
1403636670013555456
1403636670063555584
1403636670113555456
1403636670163555584
1403636670213555456
1403636670263555584
1403636670313555456
1403636670363555584
1403636670413555456
1403636670463555584
1403636670513555456
1403636670563555584
1403636670613555456
1403636670663555584
1403636670713555456
1403636670763555584
1403636670813555456
1403636670863555584
1403636670913555456
1403636670963555584
1403636671013555456
1403636671063555584
1403636671113555456
1403636671163555584
1403636671213555456
1403636671263555584
1403636671313555456
1403636671363555584
1403636671413555456
1403636671463555584
1403636671513555456
1403636671563555584
1403636671613555456
1403636671663555584
1403636671713555456
1403636671763555584
1403636671813555456
1403636671863555584
1403636671913555456
1403636671963555584
1403636672013555456
1403636672063555584
1403636672113555456
1403636672163555584
1403636672213555456
1403636672263555584
1403636672313555456
1403636672363555584
1403636672413555456
1403636672463555584
1403636672513555456
1403636672563555584
1403636672613555456
1403636672663555584
1403636672713555456
1403636672763555584
1403636672813555456
1403636672863555584
1403636672913555456
1403636672963555584
1403636673013555456
1403636673063555584
1403636673113555456
1403636673163555584
1403636673213555456
1403636673263555584
1403636673313555456
1403636673363555584
1403636673413555456
1403636673463555584
1403636673513555456
1403636673563555584
1403636673613555456
1403636673663555584
1403636673713555456
1403636673763555584
1403636673813555456
1403636673863555584
1403636673913555456
1403636673963555584
1403636674013555456
1403636674063555584
1403636674113555456
1403636674163555584
1403636674213555456
1403636674263555584
1403636674313555456
1403636674363555584
1403636674413555456
1403636674463555584
1403636674513555456
1403636674563555584
1403636674613555456
1403636674663555584
1403636674713555456
1403636674763555584
1403636674813555456
1403636674863555584
1403636674913555456
1403636674963555584
1403636675013555456
1403636675063555584
1403636675113555456
1403636675163555584
1403636675213555456
1403636675263555584
1403636675313555456
1403636675363555584
1403636675413555456
1403636675463555584
1403636675513555456
1403636675563555584
1403636675613555456
1403636675663555584
1403636675713555456
1403636675763555584
1403636675813555456
1403636675863555584
1403636675913555456
1403636675963555584
1403636676013555456
1403636676063555584
1403636676113555456
1403636676163555584
1403636676213555456
1403636676263555584
1403636676313555456
1403636676363555584
1403636676413555456
1403636676463555584
1403636676513555456
1403636676563555584
1403636676613555456
1403636676663555584
1403636676713555456
1403636676763555584
1403636676813555456
1403636676863555584
1403636676913555456
1403636676963555584
1403636677013555456
1403636677063555584
1403636677113555456
1403636677163555584
1403636677213555456
1403636677263555584
1403636677313555456
1403636677363555584
1403636677413555456
1403636677463555584
1403636677513555456
1403636677563555584
1403636677613555456
1403636677663555584
1403636677713555456
1403636677763555584
1403636677813555456
1403636677863555584
1403636677913555456
1403636677963555584
1403636678013555456
1403636678063555584
1403636678113555456
1403636678163555584
1403636678213555456
1403636678263555584
1403636678313555456
1403636678363555584
1403636678413555456
1403636678463555584
1403636678513555456
1403636678563555584
1403636678613555456
1403636678663555584
1403636678713555456
1403636678763555584
1403636678813555456
1403636678863555584
1403636678913555456
1403636678963555584
1403636679013555456
1403636679063555584
1403636679113555456
1403636679163555584
1403636679213555456
1403636679263555584
1403636679313555456
1403636679363555584
1403636679413555456
1403636679463555584
1403636679513555456
1403636679563555584
1403636679613555456
1403636679663555584
1403636679713555456
1403636679763555584
1403636679813555456
1403636679863555584
1403636679913555456
1403636679963555584
1403636680013555456
1403636680063555584
1403636680113555456
1403636680163555584
1403636680213555456
1403636680263555584
1403636680313555456
1403636680363555584
1403636680413555456
1403636680463555584
1403636680513555456
1403636680563555584
1403636680613555456
1403636680663555584
1403636680713555456
1403636680763555584
1403636680813555456
1403636680863555584
1403636680913555456
1403636680963555584
1403636681013555456
1403636681063555584
1403636681113555456
1403636681163555584
1403636681213555456
1403636681263555584
1403636681313555456
1403636681363555584
1403636681413555456
1403636681463555584
1403636681513555456
1403636681563555584
1403636681613555456
1403636681663555584
1403636681713555456
1403636681763555584
1403636681813555456
1403636681863555584
1403636681913555456
1403636681963555584
1403636682013555456
1403636682063555584
1403636682113555456
1403636682163555584
1403636682213555456
1403636682263555584
1403636682313555456
1403636682363555584
1403636682413555456
1403636682463555584
1403636682513555456
1403636682563555584
1403636682613555456
1403636682663555584
1403636682713555456
1403636682763555584
1403636682813555456
1403636682863555584
1403636682913555456
1403636682963555584
1403636683013555456
1403636683063555584
1403636683113555456
1403636683163555584
1403636683213555456
1403636683263555584
1403636683313555456
1403636683363555584
1403636683413555456
1403636683463555584
1403636683513555456
1403636683563555584
1403636683613555456
1403636683663555584
1403636683713555456
1403636683763555584
1403636683813555456
1403636683863555584
1403636683913555456
1403636683963555584
1403636684013555456
1403636684063555584
1403636684113555456
1403636684163555584
1403636684213555456
1403636684263555584
1403636684313555456
1403636684363555584
1403636684413555456
1403636684463555584
1403636684513555456
1403636684563555584
1403636684613555456
1403636684663555584
1403636684713555456
1403636684763555584
1403636684813555456
1403636684863555584
1403636684913555456
1403636684963555584
1403636685013555456
1403636685063555584
1403636685113555456
1403636685163555584
1403636685213555456
1403636685263555584
1403636685313555456
1403636685363555584
1403636685413555456
1403636685463555584
1403636685513555456
1403636685563555584
1403636685613555456
1403636685663555584
1403636685713555456
1403636685763555584
1403636685813555456
1403636685863555584
1403636685913555456
1403636685963555584
1403636686013555456
1403636686063555584
1403636686113555456
1403636686163555584
1403636686213555456
1403636686263555584
1403636686313555456
1403636686363555584
1403636686413555456
1403636686463555584
1403636686513555456
1403636686563555584
1403636686613555456
1403636686663555584
1403636686713555456
1403636686763555584
1403636686813555456
1403636686863555584
1403636686913555456
1403636686963555584
1403636687013555456
1403636687063555584
1403636687113555456
1403636687163555584
1403636687213555456
1403636687263555584
1403636687313555456
1403636687363555584
1403636687413555456
1403636687463555584
1403636687513555456
1403636687563555584
1403636687613555456
1403636687663555584
1403636687713555456
1403636687763555584
1403636687813555456
1403636687863555584
1403636687913555456
1403636687963555584
1403636688013555456
1403636688063555584
1403636688113555456
1403636688163555584
1403636688213555456
1403636688263555584
1403636688313555456
1403636688363555584
1403636688413555456
1403636688463555584
1403636688513555456
1403636688563555584
1403636688613555456
1403636688663555584
1403636688713555456
1403636688763555584
1403636688813555456
1403636688863555584
1403636688913555456
1403636688963555584
1403636689013555456
1403636689063555584
1403636689113555456
1403636689163555584
1403636689213555456
1403636689263555584
1403636689313555456
1403636689363555584
1403636689413555456
1403636689463555584
1403636689513555456
1403636689563555584
1403636689613555456
1403636689663555584
1403636689713555456
1403636689763555584
1403636689813555456
1403636689863555584
1403636689913555456
1403636689963555584
1403636690013555456
1403636690063555584
1403636690113555456
1403636690163555584
1403636690213555456
1403636690263555584
1403636690313555456
1403636690363555584
1403636690413555456
1403636690463555584
1403636690513555456
1403636690563555584
1403636690613555456
1403636690663555584
1403636690713555456
1403636690763555584
1403636690813555456
1403636690863555584
1403636690913555456
1403636690963555584
1403636691013555456
1403636691063555584
1403636691113555456
1403636691163555584
1403636691213555456
1403636691263555584
1403636691313555456
1403636691363555584
1403636691413555456
1403636691463555584
1403636691513555456
1403636691563555584
1403636691613555456
1403636691663555584
1403636691713555456
1403636691763555584
1403636691813555456
1403636691863555584
1403636691913555456
1403636691963555584
1403636692013555456
1403636692063555584
1403636692113555456
1403636692163555584
1403636692213555456
1403636692263555584
1403636692313555456
1403636692363555584
1403636692413555456
1403636692463555584
1403636692513555456
1403636692563555584
1403636692613555456
1403636692663555584
1403636692713555456
1403636692763555584
1403636692813555456
1403636692863555584
1403636692913555456
1403636692963555584
1403636693013555456
1403636693063555584
1403636693113555456
1403636693163555584
1403636693213555456
1403636693263555584
1403636693313555456
1403636693363555584
1403636693413555456
1403636693463555584
1403636693513555456
1403636693563555584
1403636693613555456
1403636693663555584
1403636693713555456
1403636693763555584
1403636693813555456
1403636693863555584
1403636693913555456
1403636693963555584
1403636694013555456
1403636694063555584
1403636694113555456
1403636694163555584
1403636694213555456
1403636694263555584
1403636694313555456
1403636694363555584
1403636694413555456
1403636694463555584
1403636694513555456
1403636694563555584
1403636694613555456
1403636694663555584
1403636694713555456
1403636694763555584
1403636694813555456
1403636694863555584
1403636694913555456
1403636694963555584
1403636695013555456
1403636695063555584
1403636695113555456
1403636695163555584
1403636695213555456
1403636695263555584
1403636695313555456
1403636695363555584
1403636695413555456
1403636695463555584
1403636695513555456
1403636695563555584
1403636695613555456
1403636695663555584
1403636695713555456
1403636695763555584
1403636695813555456
1403636695863555584
1403636695913555456
1403636695963555584
1403636696013555456
1403636696063555584
1403636696113555456
1403636696163555584
1403636696213555456
1403636696263555584
1403636696313555456
1403636696363555584
1403636696413555456
1403636696463555584
1403636696513555456
1403636696563555584
1403636696613555456
1403636696663555584
1403636696713555456
1403636696763555584
1403636696813555456
1403636696863555584
1403636696913555456
1403636696963555584
1403636697013555456
1403636697063555584
1403636697113555456
1403636697163555584
1403636697213555456
1403636697263555584
1403636697313555456
1403636697363555584
1403636697413555456
1403636697463555584
1403636697513555456
1403636697563555584
1403636697613555456
1403636697663555584
1403636697713555456
1403636697763555584
1403636697813555456
1403636697863555584
1403636697913555456
1403636697963555584
1403636698013555456
1403636698063555584
1403636698113555456
1403636698163555584
1403636698213555456
1403636698263555584
1403636698313555456
1403636698363555584
1403636698413555456
1403636698463555584
1403636698513555456
1403636698563555584
1403636698613555456
1403636698663555584
1403636698713555456
1403636698763555584
1403636698813555456
1403636698863555584
1403636698913555456
1403636698963555584
1403636699013555456
1403636699063555584
1403636699113555456
1403636699163555584
1403636699213555456
1403636699263555584
1403636699313555456
1403636699363555584
1403636699413555456
1403636699463555584
1403636699513555456
1403636699563555584
1403636699613555456
1403636699663555584
1403636699713555456
1403636699763555584
1403636699813555456
1403636699863555584
1403636699913555456
1403636699963555584
1403636700013555456
1403636700063555584
1403636700113555456
1403636700163555584
1403636700213555456
1403636700263555584
1403636700313555456
1403636700363555584
1403636700413555456
1403636700463555584
1403636700513555456
1403636700563555584
1403636700613555456
1403636700663555584
1403636700713555456
1403636700763555584
1403636700813555456
1403636700863555584
1403636700913555456
1403636700963555584
1403636701013555456
1403636701063555584
1403636701113555456
1403636701163555584
1403636701213555456
1403636701263555584
1403636701313555456
1403636701363555584
1403636701413555456
1403636701463555584
1403636701513555456
1403636701563555584
1403636701613555456
1403636701663555584
1403636701713555456
1403636701763555584
1403636701813555456
1403636701863555584
1403636701913555456
1403636701963555584
1403636702013555456
1403636702063555584
1403636702113555456
1403636702163555584
1403636702213555456
1403636702263555584
1403636702313555456
1403636702363555584
1403636702413555456
1403636702463555584
1403636702513555456
1403636702563555584
1403636702613555456
1403636702663555584
1403636702713555456
1403636702763555584
1403636702813555456
1403636702863555584
1403636702913555456
1403636702963555584
1403636703013555456
1403636703063555584
1403636703113555456
1403636703163555584
1403636703213555456
1403636703263555584
1403636703313555456
1403636703363555584
1403636703413555456
1403636703463555584
1403636703513555456
1403636703563555584
1403636703613555456
1403636703663555584
1403636703713555456
1403636703763555584
1403636703813555456
1403636703863555584
1403636703913555456
1403636703963555584
1403636704013555456
1403636704063555584
1403636704113555456
1403636704163555584
1403636704213555456
1403636704263555584
1403636704313555456
1403636704363555584
1403636704413555456
1403636704463555584
1403636704513555456
1403636704563555584
1403636704613555456
1403636704663555584
1403636704713555456
1403636704763555584
1403636704813555456
1403636704863555584
1403636704913555456
1403636704963555584
1403636705013555456
1403636705063555584
1403636705113555456
1403636705163555584
1403636705213555456
1403636705263555584
1403636705313555456
1403636705363555584
1403636705413555456
1403636705463555584
1403636705513555456
1403636705563555584
1403636705613555456
1403636705663555584
1403636705713555456
1403636705763555584
1403636705813555456
1403636705863555584
1403636705913555456
1403636705963555584
1403636706013555456
1403636706063555584
1403636706113555456
1403636706163555584
1403636706213555456
1403636706263555584
1403636706313555456
1403636706363555584
1403636706413555456
1403636706463555584
1403636706513555456
1403636706563555584
1403636706613555456
1403636706663555584
1403636706713555456
1403636706763555584
1403636706813555456
1403636706863555584
1403636706913555456
1403636706963555584
1403636707013555456
1403636707063555584
1403636707113555456
1403636707163555584
1403636707213555456
1403636707263555584
1403636707313555456
1403636707363555584
1403636707413555456
1403636707463555584
1403636707513555456
1403636707563555584
1403636707613555456
1403636707663555584
1403636707713555456
1403636707763555584
1403636707813555456
1403636707863555584
1403636707913555456
1403636707963555584
1403636708013555456
1403636708063555584
1403636708113555456
1403636708163555584
1403636708213555456
1403636708263555584
1403636708313555456
1403636708363555584
1403636708413555456
1403636708463555584
1403636708513555456
1403636708563555584
1403636708613555456
1403636708663555584
1403636708713555456
1403636708763555584
1403636708813555456
1403636708863555584
1403636708913555456
1403636708963555584
1403636709013555456
1403636709063555584
1403636709113555456
1403636709163555584
1403636709213555456
1403636709263555584
1403636709313555456
1403636709363555584
1403636709413555456
1403636709463555584
1403636709513555456
1403636709563555584
1403636709613555456
1403636709663555584
1403636709713555456
1403636709763555584
1403636709813555456
1403636709863555584
1403636709913555456
1403636709963555584
1403636710013555456
1403636710063555584
1403636710113555456
1403636710163555584
1403636710213555456
1403636710263555584
1403636710313555456
1403636710363555584
1403636710413555456
1403636710463555584
1403636710513555456
1403636710563555584
1403636710613555456
1403636710663555584
1403636710713555456
1403636710763555584
1403636710813555456
1403636710863555584
1403636710913555456
1403636710963555584
1403636711013555456
1403636711063555584
1403636711113555456
1403636711163555584
1403636711213555456
1403636711263555584
1403636711313555456
1403636711363555584
1403636711413555456
1403636711463555584
1403636711513555456
1403636711563555584
1403636711613555456
1403636711663555584
1403636711713555456
1403636711763555584
1403636711813555456
1403636711863555584
1403636711913555456
1403636711963555584
1403636712013555456
1403636712063555584
1403636712113555456
1403636712163555584
1403636712213555456
1403636712263555584
1403636712313555456
1403636712363555584
1403636712413555456
1403636712463555584
1403636712513555456
1403636712563555584
1403636712613555456
1403636712663555584
1403636712713555456
1403636712763555584
1403636712813555456
1403636712863555584
1403636712913555456
1403636712963555584
1403636713013555456
1403636713063555584
1403636713113555456
1403636713163555584
1403636713213555456
1403636713263555584
1403636713313555456
1403636713363555584
1403636713413555456
1403636713463555584
1403636713513555456
1403636713563555584
1403636713613555456
1403636713663555584
1403636713713555456
1403636713763555584
1403636713813555456
1403636713863555584
1403636713913555456
1403636713963555584
1403636714013555456
1403636714063555584
1403636714113555456
1403636714163555584
1403636714213555456
1403636714263555584
1403636714313555456
1403636714363555584
1403636714413555456
1403636714463555584
1403636714513555456
1403636714563555584
1403636714613555456
1403636714663555584
1403636714713555456
1403636714763555584
1403636714813555456
1403636714863555584
1403636714913555456
1403636714963555584
1403636715013555456
1403636715063555584
1403636715113555456
1403636715163555584
1403636715213555456
1403636715263555584
1403636715313555456
1403636715363555584
1403636715413555456
1403636715463555584
1403636715513555456
1403636715563555584
1403636715613555456
1403636715663555584
1403636715713555456
1403636715763555584
1403636715813555456
1403636715863555584
1403636715913555456
1403636715963555584
1403636716013555456
1403636716063555584
1403636716113555456
1403636716163555584
1403636716213555456
1403636716263555584
1403636716313555456
1403636716363555584
1403636716413555456
1403636716463555584
1403636716513555456
1403636716563555584
1403636716613555456
1403636716663555584
1403636716713555456
1403636716763555584
1403636716813555456
1403636716863555584
1403636716913555456
1403636716963555584
1403636717013555456
1403636717063555584
1403636717113555456
1403636717163555584
1403636717213555456
1403636717263555584
1403636717313555456
1403636717363555584
1403636717413555456
1403636717463555584
1403636717513555456
1403636717563555584
1403636717613555456
1403636717663555584
1403636717713555456
1403636717763555584
1403636717813555456
1403636717863555584
1403636717913555456
1403636717963555584
1403636718013555456
1403636718063555584
1403636718113555456
1403636718163555584
1403636718213555456
1403636718263555584
1403636718313555456
1403636718363555584
1403636718413555456
1403636718463555584
1403636718513555456
1403636718563555584
1403636718613555456
1403636718663555584
1403636718713555456
1403636718763555584
1403636718813555456
1403636718863555584
1403636718913555456
1403636718963555584
1403636719013555456
1403636719063555584
1403636719113555456
1403636719163555584
1403636719213555456
1403636719263555584
1403636719313555456
1403636719363555584
1403636719413555456
1403636719463555584
1403636719513555456
1403636719563555584
1403636719613555456
1403636719663555584
1403636719713555456
1403636719763555584
1403636719813555456
1403636719863555584
1403636719913555456
1403636719963555584
1403636720013555456
1403636720063555584
1403636720113555456
1403636720163555584
1403636720213555456
1403636720263555584
1403636720313555456
1403636720363555584
1403636720413555456
1403636720463555584
1403636720513555456
1403636720563555584
1403636720613555456
1403636720663555584
1403636720713555456
1403636720763555584
1403636720813555456
1403636720863555584
1403636720913555456
1403636720963555584
1403636721013555456
1403636721063555584
1403636721113555456
1403636721163555584
1403636721213555456
1403636721263555584
1403636721313555456
1403636721363555584
1403636721413555456
1403636721463555584
1403636721513555456
1403636721563555584
1403636721613555456
1403636721663555584
1403636721713555456
1403636721763555584
1403636721813555456
1403636721863555584
1403636721913555456
1403636721963555584
1403636722013555456
1403636722063555584
1403636722113555456
1403636722163555584
1403636722213555456
1403636722263555584
1403636722313555456
1403636722363555584
1403636722413555456
1403636722463555584
1403636722513555456
1403636722563555584
1403636722613555456
1403636722663555584
1403636722713555456
1403636722763555584
1403636722813555456
1403636722863555584
1403636722913555456
1403636722963555584
1403636723013555456
1403636723063555584
1403636723113555456
1403636723163555584
1403636723213555456
1403636723263555584
1403636723313555456
1403636723363555584
1403636723413555456
1403636723463555584
1403636723513555456
1403636723563555584
1403636723613555456
1403636723663555584
1403636723713555456
1403636723763555584
1403636723813555456
1403636723863555584
1403636723913555456
1403636723963555584
1403636724013555456
1403636724063555584
1403636724113555456
1403636724163555584
1403636724213555456
1403636724263555584
1403636724313555456
1403636724363555584
1403636724413555456
1403636724463555584
1403636724513555456
1403636724563555584
1403636724613555456
1403636724663555584
1403636724713555456
1403636724763555584
1403636724813555456
1403636724863555584
1403636724913555456
1403636724963555584
1403636725013555456
1403636725063555584
1403636725113555456
1403636725163555584
1403636725213555456
1403636725263555584
1403636725313555456
1403636725363555584
1403636725413555456
1403636725463555584
1403636725513555456
1403636725563555584
1403636725613555456
1403636725663555584
1403636725713555456
1403636725763555584
1403636725813555456
1403636725863555584
1403636725913555456
1403636725963555584
1403636726013555456
1403636726063555584
1403636726113555456
1403636726163555584
1403636726213555456
1403636726263555584
1403636726313555456
1403636726363555584
1403636726413555456
1403636726463555584
1403636726513555456
1403636726563555584
1403636726613555456
1403636726663555584
1403636726713555456
1403636726763555584
1403636726813555456
1403636726863555584
1403636726913555456
1403636726963555584
1403636727013555456
1403636727063555584
1403636727113555456
1403636727163555584
1403636727213555456
1403636727263555584
1403636727313555456
1403636727363555584
1403636727413555456
1403636727463555584
1403636727513555456
1403636727563555584
1403636727613555456
1403636727663555584
1403636727713555456
1403636727763555584
1403636727813555456
1403636727863555584
1403636727913555456
1403636727963555584
1403636728013555456
1403636728063555584
1403636728113555456
1403636728163555584
1403636728213555456
1403636728263555584
1403636728313555456
1403636728363555584
1403636728413555456
1403636728463555584
1403636728513555456
1403636728563555584
1403636728613555456
1403636728663555584
1403636728713555456
1403636728763555584
1403636728813555456
1403636728863555584
1403636728913555456
1403636728963555584
1403636729013555456
1403636729063555584
1403636729113555456
1403636729163555584
1403636729213555456
1403636729263555584
1403636729313555456
1403636729363555584
1403636729413555456
1403636729463555584
1403636729513555456
1403636729563555584
1403636729613555456
1403636729663555584
1403636729713555456
1403636729763555584
1403636729813555456
1403636729863555584
1403636729913555456
1403636729963555584
1403636730013555456
1403636730063555584
1403636730113555456
1403636730163555584
1403636730213555456
1403636730263555584
1403636730313555456
1403636730363555584
1403636730413555456
1403636730463555584
1403636730513555456
1403636730563555584
1403636730613555456
1403636730663555584
1403636730713555456
1403636730763555584
1403636730813555456
1403636730863555584
1403636730913555456
1403636730963555584
1403636731013555456
1403636731063555584
1403636731113555456
1403636731163555584
1403636731213555456
1403636731263555584
1403636731313555456
1403636731363555584
1403636731413555456
1403636731463555584
1403636731513555456
1403636731563555584
1403636731613555456
1403636731663555584
1403636731713555456
1403636731763555584
1403636731813555456
1403636731863555584
1403636731913555456
1403636731963555584
1403636732013555456
1403636732063555584
1403636732113555456
1403636732163555584
1403636732213555456
1403636732263555584
1403636732313555456
1403636732363555584
1403636732413555456
1403636732463555584
1403636732513555456
1403636732563555584
1403636732613555456
1403636732663555584
1403636732713555456
1403636732763555584
1403636732813555456
1403636732863555584
1403636732913555456
1403636732963555584
1403636733013555456
1403636733063555584
1403636733113555456
1403636733163555584
1403636733213555456
1403636733263555584
1403636733313555456
1403636733363555584
1403636733413555456
1403636733463555584
1403636733513555456
1403636733563555584
1403636733613555456
1403636733663555584
1403636733713555456
1403636733763555584
1403636733813555456
1403636733863555584
1403636733913555456
1403636733963555584
1403636734013555456
1403636734063555584
1403636734113555456
1403636734163555584
1403636734213555456
1403636734263555584
1403636734313555456
1403636734363555584
1403636734413555456
1403636734463555584
1403636734513555456
1403636734563555584
1403636734613555456
1403636734663555584
1403636734713555456
1403636734763555584
1403636734813555456
1403636734863555584
1403636734913555456
1403636734963555584
1403636735013555456
1403636735063555584
1403636735113555456
1403636735163555584
1403636735213555456
1403636735263555584
1403636735313555456
1403636735363555584
1403636735413555456
1403636735463555584
1403636735513555456
1403636735563555584
1403636735613555456
1403636735663555584
1403636735713555456
1403636735763555584
1403636735813555456
1403636735863555584
1403636735913555456
1403636735963555584
1403636736013555456
1403636736063555584
1403636736113555456
1403636736163555584
1403636736213555456
1403636736263555584
1403636736313555456
1403636736363555584
1403636736413555456
1403636736463555584
1403636736513555456
1403636736563555584
1403636736613555456
1403636736663555584
1403636736713555456
1403636736763555584
1403636736813555456
1403636736863555584
1403636736913555456
1403636736963555584
1403636737013555456
1403636737063555584
1403636737113555456
1403636737163555584
1403636737213555456
1403636737263555584
1403636737313555456
1403636737363555584
1403636737413555456
1403636737463555584
1403636737513555456
1403636737563555584
1403636737613555456
1403636737663555584
1403636737713555456
1403636737763555584
1403636737813555456
1403636737863555584
1403636737913555456
1403636737963555584
1403636738013555456
1403636738063555584
1403636738113555456
1403636738163555584
1403636738213555456
1403636738263555584
1403636738313555456
1403636738363555584
1403636738413555456
1403636738463555584
1403636738513555456
1403636738563555584
1403636738613555456
1403636738663555584
1403636738713555456
1403636738763555584
1403636738813555456
1403636738863555584
1403636738913555456
1403636738963555584
1403636739013555456
1403636739063555584
1403636739113555456
1403636739163555584
1403636739213555456
1403636739263555584
1403636739313555456
1403636739363555584
1403636739413555456
1403636739463555584
1403636739513555456
1403636739563555584
1403636739613555456
1403636739663555584
1403636739713555456
1403636739763555584
1403636739813555456
1403636739863555584
1403636739913555456
1403636739963555584
1403636740013555456
1403636740063555584
1403636740113555456
1403636740163555584
1403636740213555456
1403636740263555584
1403636740313555456
1403636740363555584
1403636740413555456
1403636740463555584
1403636740513555456
1403636740563555584
1403636740613555456
1403636740663555584
1403636740713555456
1403636740763555584
1403636740813555456
1403636740863555584
1403636740913555456
1403636740963555584
1403636741013555456
1403636741063555584
1403636741113555456
1403636741163555584
1403636741213555456
1403636741263555584
1403636741313555456
1403636741363555584
1403636741413555456
1403636741463555584
1403636741513555456
1403636741563555584
1403636741613555456
1403636741663555584
1403636741713555456
1403636741763555584
1403636741813555456
1403636741863555584
1403636741913555456
1403636741963555584
1403636742013555456
1403636742063555584
1403636742113555456
1403636742163555584
1403636742213555456
1403636742263555584
1403636742313555456
1403636742363555584
1403636742413555456
1403636742463555584
1403636742513555456
1403636742563555584
1403636742613555456
1403636742663555584
1403636742713555456
1403636742763555584
1403636742813555456
1403636742863555584
1403636742913555456
1403636742963555584
1403636743013555456
1403636743063555584
1403636743113555456
1403636743163555584
1403636743213555456
1403636743263555584
1403636743313555456
1403636743363555584
1403636743413555456
1403636743463555584
1403636743513555456
1403636743563555584
1403636743613555456
1403636743663555584
1403636743713555456
1403636743763555584
1403636743813555456
1403636743863555584
1403636743913555456
1403636743963555584
1403636744013555456
1403636744063555584
1403636744113555456
1403636744163555584
1403636744213555456
1403636744263555584
1403636744313555456
1403636744363555584
1403636744413555456
1403636744463555584
1403636744513555456
1403636744563555584
1403636744613555456
1403636744663555584
1403636744713555456
1403636744763555584
1403636744813555456
1403636744863555584
1403636744913555456
1403636744963555584
1403636745013555456
1403636745063555584
1403636745113555456
1403636745163555584
1403636745213555456
1403636745263555584
1403636745313555456
1403636745363555584
1403636745413555456
1403636745463555584
1403636745513555456
1403636745563555584
1403636745613555456
1403636745663555584
1403636745713555456
1403636745763555584
1403636745813555456
1403636745863555584
1403636745913555456
1403636745963555584
1403636746013555456
1403636746063555584
1403636746113555456
1403636746163555584
1403636746213555456
1403636746263555584
1403636746313555456
1403636746363555584
1403636746413555456
1403636746463555584
1403636746513555456
1403636746563555584
1403636746613555456
1403636746663555584
1403636746713555456
1403636746763555584
1403636746813555456
1403636746863555584
1403636746913555456
1403636746963555584
1403636747013555456
1403636747063555584
1403636747113555456
1403636747163555584
1403636747213555456
1403636747263555584
1403636747313555456
1403636747363555584
1403636747413555456
1403636747463555584
1403636747513555456
1403636747563555584
1403636747613555456
1403636747663555584
1403636747713555456
1403636747763555584
1403636747813555456
1403636747863555584
1403636747913555456
1403636747963555584
1403636748013555456
1403636748063555584
1403636748113555456
1403636748163555584
1403636748213555456
1403636748263555584
1403636748313555456
1403636748363555584
1403636748413555456
1403636748463555584
1403636748513555456
1403636748563555584
1403636748613555456
1403636748663555584
1403636748713555456
1403636748763555584
1403636748813555456
1403636748863555584
1403636748913555456
1403636748963555584
1403636749013555456
1403636749063555584
1403636749113555456
1403636749163555584
1403636749213555456
1403636749263555584
1403636749313555456
1403636749363555584
1403636749413555456
1403636749463555584
1403636749513555456
1403636749563555584
1403636749613555456
1403636749663555584
1403636749713555456
1403636749763555584
1403636749813555456
1403636749863555584
1403636749913555456
1403636749963555584
1403636750013555456
1403636750063555584
1403636750113555456
1403636750163555584
1403636750213555456
1403636750263555584
1403636750313555456
1403636750363555584
1403636750413555456
1403636750463555584
1403636750513555456
1403636750563555584
1403636750613555456
1403636750663555584
1403636750713555456
1403636750763555584
1403636750813555456
1403636750863555584
1403636750913555456
1403636750963555584
1403636751013555456
1403636751063555584
1403636751113555456
1403636751163555584
1403636751213555456
1403636751263555584
1403636751313555456
1403636751363555584
1403636751413555456
1403636751463555584
1403636751513555456
1403636751563555584
1403636751613555456
1403636751663555584
1403636751713555456
1403636751763555584
1403636751813555456
1403636751863555584
1403636751913555456
1403636751963555584
1403636752013555456
1403636752063555584
1403636752113555456
1403636752163555584
1403636752213555456
1403636752263555584
1403636752313555456
1403636752363555584
1403636752413555456
1403636752463555584
1403636752513555456
1403636752563555584
1403636752613555456
1403636752663555584
1403636752713555456
1403636752763555584
1403636752813555456
1403636752863555584
1403636752913555456
1403636752963555584
1403636753013555456
1403636753063555584
1403636753113555456
1403636753163555584
1403636753213555456
1403636753263555584
1403636753313555456
1403636753363555584
1403636753413555456
1403636753463555584
1403636753513555456
1403636753563555584
1403636753613555456
1403636753663555584
1403636753713555456
1403636753763555584
1403636753813555456
1403636753863555584
1403636753913555456
1403636753963555584
1403636754013555456
1403636754063555584
1403636754113555456
1403636754163555584
1403636754213555456
1403636754263555584
1403636754313555456
1403636754363555584
1403636754413555456
1403636754463555584
1403636754513555456
1403636754563555584
1403636754613555456
1403636754663555584
1403636754713555456
1403636754763555584
1403636754813555456
1403636754863555584
1403636754913555456
1403636754963555584
1403636755013555456
1403636755063555584
1403636755113555456
1403636755163555584
1403636755213555456
1403636755263555584
1403636755313555456
1403636755363555584
1403636755413555456
1403636755463555584
1403636755513555456
1403636755563555584
1403636755613555456
1403636755663555584
1403636755713555456
1403636755763555584
1403636755813555456
1403636755863555584
1403636755913555456
1403636755963555584
1403636756013555456
1403636756063555584
1403636756113555456
1403636756163555584
1403636756213555456
1403636756263555584
1403636756313555456
1403636756363555584
1403636756413555456
1403636756463555584
1403636756513555456
1403636756563555584
1403636756613555456
1403636756663555584
1403636756713555456
1403636756763555584
1403636756813555456
1403636756863555584
1403636756913555456
1403636756963555584
1403636757013555456
1403636757063555584
1403636757113555456
1403636757163555584
1403636757213555456
1403636757263555584
1403636757313555456
1403636757363555584
1403636757413555456
1403636757463555584
1403636757513555456
1403636757563555584
1403636757613555456
1403636757663555584
1403636757713555456
1403636757763555584
1403636757813555456
1403636757863555584
1403636757913555456
1403636757963555584
1403636758013555456
1403636758063555584
1403636758113555456
1403636758163555584
1403636758213555456
1403636758263555584
1403636758313555456
1403636758363555584
1403636758413555456
1403636758463555584
1403636758513555456
1403636758563555584
1403636758613555456
1403636758663555584
1403636758713555456
1403636758763555584
1403636758813555456
1403636758863555584
1403636758913555456
1403636758963555584
1403636759013555456
1403636759063555584
1403636759113555456
1403636759163555584
1403636759213555456
1403636759263555584
1403636759313555456
1403636759363555584
1403636759413555456
1403636759463555584
1403636759513555456
1403636759563555584
1403636759613555456
1403636759663555584
1403636759713555456
1403636759763555584
1403636759813555456
1403636759863555584
1403636759913555456
1403636759963555584
1403636760013555456
1403636760063555584
1403636760113555456
1403636760163555584
1403636760213555456
1403636760263555584
1403636760313555456
1403636760363555584
1403636760413555456
1403636760463555584
1403636760513555456
1403636760563555584
1403636760613555456
1403636760663555584
1403636760713555456
1403636760763555584
1403636760813555456
1403636760863555584
1403636760913555456
1403636760963555584
1403636761013555456
1403636761063555584
1403636761113555456
1403636761163555584
1403636761213555456
1403636761263555584
1403636761313555456
1403636761363555584
1403636761413555456
1403636761463555584
1403636761513555456
1403636761563555584
1403636761613555456
1403636761663555584
1403636761713555456
1403636761763555584
1403636761813555456
1403636761863555584
1403636761913555456
1403636761963555584
1403636762013555456
1403636762063555584
1403636762113555456
1403636762163555584
1403636762213555456
1403636762263555584
1403636762313555456
1403636762363555584
1403636762413555456
1403636762463555584
1403636762513555456
1403636762563555584
1403636762613555456
1403636762663555584
1403636762713555456
1403636762763555584
1403636762813555456
1403636762863555584
1403636762913555456
1403636762963555584
1403636763013555456
1403636763063555584
1403636763113555456
1403636763163555584
1403636763213555456
1403636763263555584
1403636763313555456
1403636763363555584
1403636763413555456
1403636763463555584
1403636763513555456
1403636763563555584
1403636763613555456
1403636763663555584
1403636763713555456
1403636763763555584
1403636763813555456
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/MH02.txt
================================================
1403636858651666432
1403636858701666560
1403636858751666432
1403636858801666560
1403636858851666432
1403636858901666560
1403636858951666432
1403636859001666560
1403636859051666432
1403636859101666560
1403636859151666432
1403636859201666560
1403636859251666432
1403636859301666560
1403636859351666432
1403636859401666560
1403636859451666432
1403636859501666560
1403636859551666432
1403636859601666560
1403636859651666432
1403636859701666560
1403636859751666432
1403636859801666560
1403636859851666432
1403636859901666560
1403636859951666432
1403636860001666560
1403636860051666432
1403636860101666560
1403636860151666432
1403636860201666560
1403636860251666432
1403636860301666560
1403636860351666432
1403636860401666560
1403636860451666432
1403636860501666560
1403636860551666432
1403636860601666560
1403636860651666432
1403636860701666560
1403636860751666432
1403636860801666560
1403636860851666432
1403636860901666560
1403636860951666432
1403636861001666560
1403636861051666432
1403636861101666560
1403636861151666432
1403636861201666560
1403636861251666432
1403636861301666560
1403636861351666432
1403636861401666560
1403636861451666432
1403636861501666560
1403636861551666432
1403636861601666560
1403636861651666432
1403636861701666560
1403636861751666432
1403636861801666560
1403636861851666432
1403636861901666560
1403636861951666432
1403636862001666560
1403636862051666432
1403636862101666560
1403636862151666432
1403636862201666560
1403636862251666432
1403636862301666560
1403636862351666432
1403636862401666560
1403636862451666432
1403636862501666560
1403636862551666432
1403636862601666560
1403636862651666432
1403636862701666560
1403636862751666432
1403636862801666560
1403636862851666432
1403636862901666560
1403636862951666432
1403636863001666560
1403636863051666432
1403636863101666560
1403636863151666432
1403636863201666560
1403636863251666432
1403636863301666560
1403636863351666432
1403636863401666560
1403636863451666432
1403636863501666560
1403636863551666432
1403636863601666560
1403636863651666432
1403636863701666560
1403636863751666432
1403636863801666560
1403636863851666432
1403636863901666560
1403636863951666432
1403636864001666560
1403636864051666432
1403636864101666560
1403636864151666432
1403636864201666560
1403636864251666432
1403636864301666560
1403636864351666432
1403636864401666560
1403636864451666432
1403636864501666560
1403636864551666432
1403636864601666560
1403636864651666432
1403636864701666560
1403636864751666432
1403636864801666560
1403636864851666432
1403636864901666560
1403636864951666432
1403636865001666560
1403636865051666432
1403636865101666560
1403636865151666432
1403636865201666560
1403636865251666432
1403636865301666560
1403636865351666432
1403636865401666560
1403636865451666432
1403636865501666560
1403636865551666432
1403636865601666560
1403636865651666432
1403636865701666560
1403636865751666432
1403636865801666560
1403636865851666432
1403636865901666560
1403636865951666432
1403636866001666560
1403636866051666432
1403636866101666560
1403636866151666432
1403636866201666560
1403636866251666432
1403636866301666560
1403636866351666432
1403636866401666560
1403636866451666432
1403636866501666560
1403636866551666432
1403636866601666560
1403636866651666432
1403636866701666560
1403636866751666432
1403636866801666560
1403636866851666432
1403636866901666560
1403636866951666432
1403636867001666560
1403636867051666432
1403636867101666560
1403636867151666432
1403636867201666560
1403636867251666432
1403636867301666560
1403636867351666432
1403636867401666560
1403636867451666432
1403636867501666560
1403636867551666432
1403636867601666560
1403636867651666432
1403636867701666560
1403636867751666432
1403636867801666560
1403636867851666432
1403636867901666560
1403636867951666432
1403636868001666560
1403636868051666432
1403636868101666560
1403636868151666432
1403636868201666560
1403636868251666432
1403636868301666560
1403636868351666432
1403636868401666560
1403636868451666432
1403636868501666560
1403636868551666432
1403636868601666560
1403636868651666432
1403636868701666560
1403636868751666432
1403636868801666560
1403636868851666432
1403636868901666560
1403636868951666432
1403636869001666560
1403636869051666432
1403636869101666560
1403636869151666432
1403636869201666560
1403636869251666432
1403636869301666560
1403636869351666432
1403636869401666560
1403636869451666432
1403636869501666560
1403636869551666432
1403636869601666560
1403636869651666432
1403636869701666560
1403636869751666432
1403636869801666560
1403636869851666432
1403636869901666560
1403636869951666432
1403636870001666560
1403636870051666432
1403636870101666560
1403636870151666432
1403636870201666560
1403636870251666432
1403636870301666560
1403636870351666432
1403636870401666560
1403636870451666432
1403636870501666560
1403636870551666432
1403636870601666560
1403636870651666432
1403636870701666560
1403636870751666432
1403636870801666560
1403636870851666432
1403636870901666560
1403636870951666432
1403636871001666560
1403636871051666432
1403636871101666560
1403636871151666432
1403636871201666560
1403636871251666432
1403636871301666560
1403636871351666432
1403636871401666560
1403636871451666432
1403636871501666560
1403636871551666432
1403636871601666560
1403636871651666432
1403636871701666560
1403636871751666432
1403636871801666560
1403636871851666432
1403636871901666560
1403636871951666432
1403636872001666560
1403636872051666432
1403636872101666560
1403636872151666432
1403636872201666560
1403636872251666432
1403636872301666560
1403636872351666432
1403636872401666560
1403636872451666432
1403636872501666560
1403636872551666432
1403636872601666560
1403636872651666432
1403636872701666560
1403636872751666432
1403636872801666560
1403636872851666432
1403636872901666560
1403636872951666432
1403636873001666560
1403636873051666432
1403636873101666560
1403636873151666432
1403636873201666560
1403636873251666432
1403636873301666560
1403636873351666432
1403636873401666560
1403636873451666432
1403636873501666560
1403636873551666432
1403636873601666560
1403636873651666432
1403636873701666560
1403636873751666432
1403636873801666560
1403636873851666432
1403636873901666560
1403636873951666432
1403636874001666560
1403636874051666432
1403636874101666560
1403636874151666432
1403636874201666560
1403636874251666432
1403636874301666560
1403636874351666432
1403636874401666560
1403636874451666432
1403636874501666560
1403636874551666432
1403636874601666560
1403636874651666432
1403636874701666560
1403636874751666432
1403636874801666560
1403636874851666432
1403636874901666560
1403636874951666432
1403636875001666560
1403636875051666432
1403636875101666560
1403636875151666432
1403636875201666560
1403636875251666432
1403636875301666560
1403636875351666432
1403636875401666560
1403636875451666432
1403636875501666560
1403636875551666432
1403636875601666560
1403636875651666432
1403636875701666560
1403636875751666432
1403636875801666560
1403636875851666432
1403636875901666560
1403636875951666432
1403636876001666560
1403636876051666432
1403636876101666560
1403636876151666432
1403636876201666560
1403636876251666432
1403636876301666560
1403636876351666432
1403636876401666560
1403636876451666432
1403636876501666560
1403636876551666432
1403636876601666560
1403636876651666432
1403636876701666560
1403636876751666432
1403636876801666560
1403636876851666432
1403636876901666560
1403636876951666432
1403636877001666560
1403636877051666432
1403636877101666560
1403636877151666432
1403636877201666560
1403636877251666432
1403636877301666560
1403636877351666432
1403636877401666560
1403636877451666432
1403636877501666560
1403636877551666432
1403636877601666560
1403636877651666432
1403636877701666560
1403636877751666432
1403636877801666560
1403636877851666432
1403636877901666560
1403636877951666432
1403636878001666560
1403636878051666432
1403636878101666560
1403636878151666432
1403636878201666560
1403636878251666432
1403636878301666560
1403636878351666432
1403636878401666560
1403636878451666432
1403636878501666560
1403636878551666432
1403636878601666560
1403636878651666432
1403636878701666560
1403636878751666432
1403636878801666560
1403636878851666432
1403636878901666560
1403636878951666432
1403636879001666560
1403636879051666432
1403636879101666560
1403636879151666432
1403636879201666560
1403636879251666432
1403636879301666560
1403636879351666432
1403636879401666560
1403636879451666432
1403636879501666560
1403636879551666432
1403636879601666560
1403636879651666432
1403636879701666560
1403636879751666432
1403636879801666560
1403636879851666432
1403636879901666560
1403636879951666432
1403636880001666560
1403636880051666432
1403636880101666560
1403636880151666432
1403636880201666560
1403636880251666432
1403636880301666560
1403636880351666432
1403636880401666560
1403636880451666432
1403636880501666560
1403636880551666432
1403636880601666560
1403636880651666432
1403636880701666560
1403636880751666432
1403636880801666560
1403636880851666432
1403636880901666560
1403636880951666432
1403636881001666560
1403636881051666432
1403636881101666560
1403636881151666432
1403636881201666560
1403636881251666432
1403636881301666560
1403636881351666432
1403636881401666560
1403636881451666432
1403636881501666560
1403636881551666432
1403636881601666560
1403636881651666432
1403636881701666560
1403636881751666432
1403636881801666560
1403636881851666432
1403636881901666560
1403636881951666432
1403636882001666560
1403636882051666432
1403636882101666560
1403636882151666432
1403636882201666560
1403636882251666432
1403636882301666560
1403636882351666432
1403636882401666560
1403636882451666432
1403636882501666560
1403636882551666432
1403636882601666560
1403636882651666432
1403636882701666560
1403636882751666432
1403636882801666560
1403636882851666432
1403636882901666560
1403636882951666432
1403636883001666560
1403636883051666432
1403636883101666560
1403636883151666432
1403636883201666560
1403636883251666432
1403636883301666560
1403636883351666432
1403636883401666560
1403636883451666432
1403636883501666560
1403636883551666432
1403636883601666560
1403636883651666432
1403636883701666560
1403636883751666432
1403636883801666560
1403636883851666432
1403636883901666560
1403636883951666432
1403636884001666560
1403636884051666432
1403636884101666560
1403636884151666432
1403636884201666560
1403636884251666432
1403636884301666560
1403636884351666432
1403636884401666560
1403636884451666432
1403636884501666560
1403636884551666432
1403636884601666560
1403636884651666432
1403636884701666560
1403636884751666432
1403636884801666560
1403636884851666432
1403636884901666560
1403636884951666432
1403636885001666560
1403636885051666432
1403636885101666560
1403636885151666432
1403636885201666560
1403636885251666432
1403636885301666560
1403636885351666432
1403636885401666560
1403636885451666432
1403636885501666560
1403636885551666432
1403636885601666560
1403636885651666432
1403636885701666560
1403636885751666432
1403636885801666560
1403636885851666432
1403636885901666560
1403636885951666432
1403636886001666560
1403636886051666432
1403636886101666560
1403636886151666432
1403636886201666560
1403636886251666432
1403636886301666560
1403636886351666432
1403636886401666560
1403636886451666432
1403636886501666560
1403636886551666432
1403636886601666560
1403636886651666432
1403636886701666560
1403636886751666432
1403636886801666560
1403636886851666432
1403636886901666560
1403636886951666432
1403636887001666560
1403636887051666432
1403636887101666560
1403636887151666432
1403636887201666560
1403636887251666432
1403636887301666560
1403636887351666432
1403636887401666560
1403636887451666432
1403636887501666560
1403636887551666432
1403636887601666560
1403636887651666432
1403636887701666560
1403636887751666432
1403636887801666560
1403636887851666432
1403636887901666560
1403636887951666432
1403636888001666560
1403636888051666432
1403636888101666560
1403636888151666432
1403636888201666560
1403636888251666432
1403636888301666560
1403636888351666432
1403636888401666560
1403636888451666432
1403636888501666560
1403636888551666432
1403636888601666560
1403636888651666432
1403636888701666560
1403636888751666432
1403636888801666560
1403636888851666432
1403636888901666560
1403636888951666432
1403636889001666560
1403636889051666432
1403636889101666560
1403636889151666432
1403636889201666560
1403636889251666432
1403636889301666560
1403636889351666432
1403636889401666560
1403636889451666432
1403636889501666560
1403636889551666432
1403636889601666560
1403636889651666432
1403636889701666560
1403636889751666432
1403636889801666560
1403636889851666432
1403636889901666560
1403636889951666432
1403636890001666560
1403636890051666432
1403636890101666560
1403636890151666432
1403636890201666560
1403636890251666432
1403636890301666560
1403636890351666432
1403636890401666560
1403636890451666432
1403636890501666560
1403636890551666432
1403636890601666560
1403636890651666432
1403636890701666560
1403636890751666432
1403636890801666560
1403636890851666432
1403636890901666560
1403636890951666432
1403636891001666560
1403636891051666432
1403636891101666560
1403636891151666432
1403636891201666560
1403636891251666432
1403636891301666560
1403636891351666432
1403636891401666560
1403636891451666432
1403636891501666560
1403636891551666432
1403636891601666560
1403636891651666432
1403636891701666560
1403636891751666432
1403636891801666560
1403636891851666432
1403636891901666560
1403636891951666432
1403636892001666560
1403636892051666432
1403636892101666560
1403636892151666432
1403636892201666560
1403636892251666432
1403636892301666560
1403636892351666432
1403636892401666560
1403636892451666432
1403636892501666560
1403636892551666432
1403636892601666560
1403636892651666432
1403636892701666560
1403636892751666432
1403636892801666560
1403636892851666432
1403636892901666560
1403636892951666432
1403636893001666560
1403636893051666432
1403636893101666560
1403636893151666432
1403636893201666560
1403636893251666432
1403636893301666560
1403636893351666432
1403636893401666560
1403636893451666432
1403636893501666560
1403636893551666432
1403636893601666560
1403636893651666432
1403636893701666560
1403636893751666432
1403636893801666560
1403636893851666432
1403636893901666560
1403636893951666432
1403636894001666560
1403636894051666432
1403636894101666560
1403636894151666432
1403636894201666560
1403636894251666432
1403636894301666560
1403636894351666432
1403636894401666560
1403636894451666432
1403636894501666560
1403636894551666432
1403636894601666560
1403636894651666432
1403636894701666560
1403636894751666432
1403636894801666560
1403636894851666432
1403636894901666560
1403636894951666432
1403636895001666560
1403636895051666432
1403636895101666560
1403636895151666432
1403636895201666560
1403636895251666432
1403636895301666560
1403636895351666432
1403636895401666560
1403636895451666432
1403636895501666560
1403636895551666432
1403636895601666560
1403636895651666432
1403636895701666560
1403636895751666432
1403636895801666560
1403636895851666432
1403636895901666560
1403636895951666432
1403636896001666560
1403636896051666432
1403636896101666560
1403636896151666432
1403636896201666560
1403636896251666432
1403636896301666560
1403636896351666432
1403636896401666560
1403636896451666432
1403636896501666560
1403636896551666432
1403636896601666560
1403636896651666432
1403636896701666560
1403636896751666432
1403636896801666560
1403636896851666432
1403636896901666560
1403636896951666432
1403636897001666560
1403636897051666432
1403636897101666560
1403636897151666432
1403636897201666560
1403636897251666432
1403636897301666560
1403636897351666432
1403636897401666560
1403636897451666432
1403636897501666560
1403636897551666432
1403636897601666560
1403636897651666432
1403636897701666560
1403636897751666432
1403636897801666560
1403636897851666432
1403636897901666560
1403636897951666432
1403636898001666560
1403636898051666432
1403636898101666560
1403636898151666432
1403636898201666560
1403636898251666432
1403636898301666560
1403636898351666432
1403636898401666560
1403636898451666432
1403636898501666560
1403636898551666432
1403636898601666560
1403636898651666432
1403636898701666560
1403636898751666432
1403636898801666560
1403636898851666432
1403636898901666560
1403636898951666432
1403636899001666560
1403636899051666432
1403636899101666560
1403636899151666432
1403636899201666560
1403636899251666432
1403636899301666560
1403636899351666432
1403636899401666560
1403636899451666432
1403636899501666560
1403636899551666432
1403636899601666560
1403636899651666432
1403636899701666560
1403636899751666432
1403636899801666560
1403636899851666432
1403636899901666560
1403636899951666432
1403636900001666560
1403636900051666432
1403636900101666560
1403636900151666432
1403636900201666560
1403636900251666432
1403636900301666560
1403636900351666432
1403636900401666560
1403636900451666432
1403636900501666560
1403636900551666432
1403636900601666560
1403636900651666432
1403636900701666560
1403636900751666432
1403636900801666560
1403636900851666432
1403636900901666560
1403636900951666432
1403636901001666560
1403636901051666432
1403636901101666560
1403636901151666432
1403636901201666560
1403636901251666432
1403636901301666560
1403636901351666432
1403636901401666560
1403636901451666432
1403636901501666560
1403636901551666432
1403636901601666560
1403636901651666432
1403636901701666560
1403636901751666432
1403636901801666560
1403636901851666432
1403636901901666560
1403636901951666432
1403636902001666560
1403636902051666432
1403636902101666560
1403636902151666432
1403636902201666560
1403636902251666432
1403636902301666560
1403636902351666432
1403636902401666560
1403636902451666432
1403636902501666560
1403636902551666432
1403636902601666560
1403636902651666432
1403636902701666560
1403636902751666432
1403636902801666560
1403636902851666432
1403636902901666560
1403636902951666432
1403636903001666560
1403636903051666432
1403636903101666560
1403636903151666432
1403636903201666560
1403636903251666432
1403636903301666560
1403636903351666432
1403636903401666560
1403636903451666432
1403636903501666560
1403636903551666432
1403636903601666560
1403636903651666432
1403636903701666560
1403636903751666432
1403636903801666560
1403636903851666432
1403636903901666560
1403636903951666432
1403636904001666560
1403636904051666432
1403636904101666560
1403636904151666432
1403636904201666560
1403636904251666432
1403636904301666560
1403636904351666432
1403636904401666560
1403636904451666432
1403636904501666560
1403636904551666432
1403636904601666560
1403636904651666432
1403636904701666560
1403636904751666432
1403636904801666560
1403636904851666432
1403636904901666560
1403636904951666432
1403636905001666560
1403636905051666432
1403636905101666560
1403636905151666432
1403636905201666560
1403636905251666432
1403636905301666560
1403636905351666432
1403636905401666560
1403636905451666432
1403636905501666560
1403636905551666432
1403636905601666560
1403636905651666432
1403636905701666560
1403636905751666432
1403636905801666560
1403636905851666432
1403636905901666560
1403636905951666432
1403636906001666560
1403636906051666432
1403636906101666560
1403636906151666432
1403636906201666560
1403636906251666432
1403636906301666560
1403636906351666432
1403636906401666560
1403636906451666432
1403636906501666560
1403636906551666432
1403636906601666560
1403636906651666432
1403636906701666560
1403636906751666432
1403636906801666560
1403636906851666432
1403636906901666560
1403636906951666432
1403636907001666560
1403636907051666432
1403636907101666560
1403636907151666432
1403636907201666560
1403636907251666432
1403636907301666560
1403636907351666432
1403636907401666560
1403636907451666432
1403636907501666560
1403636907551666432
1403636907601666560
1403636907651666432
1403636907701666560
1403636907751666432
1403636907801666560
1403636907851666432
1403636907901666560
1403636907951666432
1403636908001666560
1403636908051666432
1403636908101666560
1403636908151666432
1403636908201666560
1403636908251666432
1403636908301666560
1403636908351666432
1403636908401666560
1403636908451666432
1403636908501666560
1403636908551666432
1403636908601666560
1403636908651666432
1403636908701666560
1403636908751666432
1403636908801666560
1403636908851666432
1403636908901666560
1403636908951666432
1403636909001666560
1403636909051666432
1403636909101666560
1403636909151666432
1403636909201666560
1403636909251666432
1403636909301666560
1403636909351666432
1403636909401666560
1403636909451666432
1403636909501666560
1403636909551666432
1403636909601666560
1403636909651666432
1403636909701666560
1403636909751666432
1403636909801666560
1403636909851666432
1403636909901666560
1403636909951666432
1403636910001666560
1403636910051666432
1403636910101666560
1403636910151666432
1403636910201666560
1403636910251666432
1403636910301666560
1403636910351666432
1403636910401666560
1403636910451666432
1403636910501666560
1403636910551666432
1403636910601666560
1403636910651666432
1403636910701666560
1403636910751666432
1403636910801666560
1403636910851666432
1403636910901666560
1403636910951666432
1403636911001666560
1403636911051666432
1403636911101666560
1403636911151666432
1403636911201666560
1403636911251666432
1403636911301666560
1403636911351666432
1403636911401666560
1403636911451666432
1403636911501666560
1403636911551666432
1403636911601666560
1403636911651666432
1403636911701666560
1403636911751666432
1403636911801666560
1403636911851666432
1403636911901666560
1403636911951666432
1403636912001666560
1403636912051666432
1403636912101666560
1403636912151666432
1403636912201666560
1403636912251666432
1403636912301666560
1403636912351666432
1403636912401666560
1403636912451666432
1403636912501666560
1403636912551666432
1403636912601666560
1403636912651666432
1403636912701666560
1403636912751666432
1403636912801666560
1403636912851666432
1403636912901666560
1403636912951666432
1403636913001666560
1403636913051666432
1403636913101666560
1403636913151666432
1403636913201666560
1403636913251666432
1403636913301666560
1403636913351666432
1403636913401666560
1403636913451666432
1403636913501666560
1403636913551666432
1403636913601666560
1403636913651666432
1403636913701666560
1403636913751666432
1403636913801666560
1403636913851666432
1403636913901666560
1403636913951666432
1403636914001666560
1403636914051666432
1403636914101666560
1403636914151666432
1403636914201666560
1403636914251666432
1403636914301666560
1403636914351666432
1403636914401666560
1403636914451666432
1403636914501666560
1403636914551666432
1403636914601666560
1403636914651666432
1403636914701666560
1403636914751666432
1403636914801666560
1403636914851666432
1403636914901666560
1403636914951666432
1403636915001666560
1403636915051666432
1403636915101666560
1403636915151666432
1403636915201666560
1403636915251666432
1403636915301666560
1403636915351666432
1403636915401666560
1403636915451666432
1403636915501666560
1403636915551666432
1403636915601666560
1403636915651666432
1403636915701666560
1403636915751666432
1403636915801666560
1403636915851666432
1403636915901666560
1403636915951666432
1403636916001666560
1403636916051666432
1403636916101666560
1403636916151666432
1403636916201666560
1403636916251666432
1403636916301666560
1403636916351666432
1403636916401666560
1403636916451666432
1403636916501666560
1403636916551666432
1403636916601666560
1403636916651666432
1403636916701666560
1403636916751666432
1403636916801666560
1403636916851666432
1403636916901666560
1403636916951666432
1403636917001666560
1403636917051666432
1403636917101666560
1403636917151666432
1403636917201666560
1403636917251666432
1403636917301666560
1403636917351666432
1403636917401666560
1403636917451666432
1403636917501666560
1403636917551666432
1403636917601666560
1403636917651666432
1403636917701666560
1403636917751666432
1403636917801666560
1403636917851666432
1403636917901666560
1403636917951666432
1403636918001666560
1403636918051666432
1403636918101666560
1403636918151666432
1403636918201666560
1403636918251666432
1403636918301666560
1403636918351666432
1403636918401666560
1403636918451666432
1403636918501666560
1403636918551666432
1403636918601666560
1403636918651666432
1403636918701666560
1403636918751666432
1403636918801666560
1403636918851666432
1403636918901666560
1403636918951666432
1403636919001666560
1403636919051666432
1403636919101666560
1403636919151666432
1403636919201666560
1403636919251666432
1403636919301666560
1403636919351666432
1403636919401666560
1403636919451666432
1403636919501666560
1403636919551666432
1403636919601666560
1403636919651666432
1403636919701666560
1403636919751666432
1403636919801666560
1403636919851666432
1403636919901666560
1403636919951666432
1403636920001666560
1403636920051666432
1403636920101666560
1403636920151666432
1403636920201666560
1403636920251666432
1403636920301666560
1403636920351666432
1403636920401666560
1403636920451666432
1403636920501666560
1403636920551666432
1403636920601666560
1403636920651666432
1403636920701666560
1403636920751666432
1403636920801666560
1403636920851666432
1403636920901666560
1403636920951666432
1403636921001666560
1403636921051666432
1403636921101666560
1403636921151666432
1403636921201666560
1403636921251666432
1403636921301666560
1403636921351666432
1403636921401666560
1403636921451666432
1403636921501666560
1403636921551666432
1403636921601666560
1403636921651666432
1403636921701666560
1403636921751666432
1403636921801666560
1403636921851666432
1403636921901666560
1403636921951666432
1403636922001666560
1403636922051666432
1403636922101666560
1403636922151666432
1403636922201666560
1403636922251666432
1403636922301666560
1403636922351666432
1403636922401666560
1403636922451666432
1403636922501666560
1403636922551666432
1403636922601666560
1403636922651666432
1403636922701666560
1403636922751666432
1403636922801666560
1403636922851666432
1403636922901666560
1403636922951666432
1403636923001666560
1403636923051666432
1403636923101666560
1403636923151666432
1403636923201666560
1403636923251666432
1403636923301666560
1403636923351666432
1403636923401666560
1403636923451666432
1403636923501666560
1403636923551666432
1403636923601666560
1403636923651666432
1403636923701666560
1403636923751666432
1403636923801666560
1403636923851666432
1403636923901666560
1403636923951666432
1403636924001666560
1403636924051666432
1403636924101666560
1403636924151666432
1403636924201666560
1403636924251666432
1403636924301666560
1403636924351666432
1403636924401666560
1403636924451666432
1403636924501666560
1403636924551666432
1403636924601666560
1403636924651666432
1403636924701666560
1403636924751666432
1403636924801666560
1403636924851666432
1403636924901666560
1403636924951666432
1403636925001666560
1403636925051666432
1403636925101666560
1403636925151666432
1403636925201666560
1403636925251666432
1403636925301666560
1403636925351666432
1403636925401666560
1403636925451666432
1403636925501666560
1403636925551666432
1403636925601666560
1403636925651666432
1403636925701666560
1403636925751666432
1403636925801666560
1403636925851666432
1403636925901666560
1403636925951666432
1403636926001666560
1403636926051666432
1403636926101666560
1403636926151666432
1403636926201666560
1403636926251666432
1403636926301666560
1403636926351666432
1403636926401666560
1403636926451666432
1403636926501666560
1403636926551666432
1403636926601666560
1403636926651666432
1403636926701666560
1403636926751666432
1403636926801666560
1403636926851666432
1403636926901666560
1403636926951666432
1403636927001666560
1403636927051666432
1403636927101666560
1403636927151666432
1403636927201666560
1403636927251666432
1403636927301666560
1403636927351666432
1403636927401666560
1403636927451666432
1403636927501666560
1403636927551666432
1403636927601666560
1403636927651666432
1403636927701666560
1403636927751666432
1403636927801666560
1403636927851666432
1403636927901666560
1403636927951666432
1403636928001666560
1403636928051666432
1403636928101666560
1403636928151666432
1403636928201666560
1403636928251666432
1403636928301666560
1403636928351666432
1403636928401666560
1403636928451666432
1403636928501666560
1403636928551666432
1403636928601666560
1403636928651666432
1403636928701666560
1403636928751666432
1403636928801666560
1403636928851666432
1403636928901666560
1403636928951666432
1403636929001666560
1403636929051666432
1403636929101666560
1403636929151666432
1403636929201666560
1403636929251666432
1403636929301666560
1403636929351666432
1403636929401666560
1403636929451666432
1403636929501666560
1403636929551666432
1403636929601666560
1403636929651666432
1403636929701666560
1403636929751666432
1403636929801666560
1403636929851666432
1403636929901666560
1403636929951666432
1403636930001666560
1403636930051666432
1403636930101666560
1403636930151666432
1403636930201666560
1403636930251666432
1403636930301666560
1403636930351666432
1403636930401666560
1403636930451666432
1403636930501666560
1403636930551666432
1403636930601666560
1403636930651666432
1403636930701666560
1403636930751666432
1403636930801666560
1403636930851666432
1403636930901666560
1403636930951666432
1403636931001666560
1403636931051666432
1403636931101666560
1403636931151666432
1403636931201666560
1403636931251666432
1403636931301666560
1403636931351666432
1403636931401666560
1403636931451666432
1403636931501666560
1403636931551666432
1403636931601666560
1403636931651666432
1403636931701666560
1403636931751666432
1403636931801666560
1403636931851666432
1403636931901666560
1403636931951666432
1403636932001666560
1403636932051666432
1403636932101666560
1403636932151666432
1403636932201666560
1403636932251666432
1403636932301666560
1403636932351666432
1403636932401666560
1403636932451666432
1403636932501666560
1403636932551666432
1403636932601666560
1403636932651666432
1403636932701666560
1403636932751666432
1403636932801666560
1403636932851666432
1403636932901666560
1403636932951666432
1403636933001666560
1403636933051666432
1403636933101666560
1403636933151666432
1403636933201666560
1403636933251666432
1403636933301666560
1403636933351666432
1403636933401666560
1403636933451666432
1403636933501666560
1403636933551666432
1403636933601666560
1403636933651666432
1403636933701666560
1403636933751666432
1403636933801666560
1403636933851666432
1403636933901666560
1403636933951666432
1403636934001666560
1403636934051666432
1403636934101666560
1403636934151666432
1403636934201666560
1403636934251666432
1403636934301666560
1403636934351666432
1403636934401666560
1403636934451666432
1403636934501666560
1403636934551666432
1403636934601666560
1403636934651666432
1403636934701666560
1403636934751666432
1403636934801666560
1403636934851666432
1403636934901666560
1403636934951666432
1403636935001666560
1403636935051666432
1403636935101666560
1403636935151666432
1403636935201666560
1403636935251666432
1403636935301666560
1403636935351666432
1403636935401666560
1403636935451666432
1403636935501666560
1403636935551666432
1403636935601666560
1403636935651666432
1403636935701666560
1403636935751666432
1403636935801666560
1403636935851666432
1403636935901666560
1403636935951666432
1403636936001666560
1403636936051666432
1403636936101666560
1403636936151666432
1403636936201666560
1403636936251666432
1403636936301666560
1403636936351666432
1403636936401666560
1403636936451666432
1403636936501666560
1403636936551666432
1403636936601666560
1403636936651666432
1403636936701666560
1403636936751666432
1403636936801666560
1403636936851666432
1403636936901666560
1403636936951666432
1403636937001666560
1403636937051666432
1403636937101666560
1403636937151666432
1403636937201666560
1403636937251666432
1403636937301666560
1403636937351666432
1403636937401666560
1403636937451666432
1403636937501666560
1403636937551666432
1403636937601666560
1403636937651666432
1403636937701666560
1403636937751666432
1403636937801666560
1403636937851666432
1403636937901666560
1403636937951666432
1403636938001666560
1403636938051666432
1403636938101666560
1403636938151666432
1403636938201666560
1403636938251666432
1403636938301666560
1403636938351666432
1403636938401666560
1403636938451666432
1403636938501666560
1403636938551666432
1403636938601666560
1403636938651666432
1403636938701666560
1403636938751666432
1403636938801666560
1403636938851666432
1403636938901666560
1403636938951666432
1403636939001666560
1403636939051666432
1403636939101666560
1403636939151666432
1403636939201666560
1403636939251666432
1403636939301666560
1403636939351666432
1403636939401666560
1403636939451666432
1403636939501666560
1403636939551666432
1403636939601666560
1403636939651666432
1403636939701666560
1403636939751666432
1403636939801666560
1403636939851666432
1403636939901666560
1403636939951666432
1403636940001666560
1403636940051666432
1403636940101666560
1403636940151666432
1403636940201666560
1403636940251666432
1403636940301666560
1403636940351666432
1403636940401666560
1403636940451666432
1403636940501666560
1403636940551666432
1403636940601666560
1403636940651666432
1403636940701666560
1403636940751666432
1403636940801666560
1403636940851666432
1403636940901666560
1403636940951666432
1403636941001666560
1403636941051666432
1403636941101666560
1403636941151666432
1403636941201666560
1403636941251666432
1403636941301666560
1403636941351666432
1403636941401666560
1403636941451666432
1403636941501666560
1403636941551666432
1403636941601666560
1403636941651666432
1403636941701666560
1403636941751666432
1403636941801666560
1403636941851666432
1403636941901666560
1403636941951666432
1403636942001666560
1403636942051666432
1403636942101666560
1403636942151666432
1403636942201666560
1403636942251666432
1403636942301666560
1403636942351666432
1403636942401666560
1403636942451666432
1403636942501666560
1403636942551666432
1403636942601666560
1403636942651666432
1403636942701666560
1403636942751666432
1403636942801666560
1403636942851666432
1403636942901666560
1403636942951666432
1403636943001666560
1403636943051666432
1403636943101666560
1403636943151666432
1403636943201666560
1403636943251666432
1403636943301666560
1403636943351666432
1403636943401666560
1403636943451666432
1403636943501666560
1403636943551666432
1403636943601666560
1403636943651666432
1403636943701666560
1403636943751666432
1403636943801666560
1403636943851666432
1403636943901666560
1403636943951666432
1403636944001666560
1403636944051666432
1403636944101666560
1403636944151666432
1403636944201666560
1403636944251666432
1403636944301666560
1403636944351666432
1403636944401666560
1403636944451666432
1403636944501666560
1403636944551666432
1403636944601666560
1403636944651666432
1403636944701666560
1403636944751666432
1403636944801666560
1403636944851666432
1403636944901666560
1403636944951666432
1403636945001666560
1403636945051666432
1403636945101666560
1403636945151666432
1403636945201666560
1403636945251666432
1403636945301666560
1403636945351666432
1403636945401666560
1403636945451666432
1403636945501666560
1403636945551666432
1403636945601666560
1403636945651666432
1403636945701666560
1403636945751666432
1403636945801666560
1403636945851666432
1403636945901666560
1403636945951666432
1403636946001666560
1403636946051666432
1403636946101666560
1403636946151666432
1403636946201666560
1403636946251666432
1403636946301666560
1403636946351666432
1403636946401666560
1403636946451666432
1403636946501666560
1403636946551666432
1403636946601666560
1403636946651666432
1403636946701666560
1403636946751666432
1403636946801666560
1403636946851666432
1403636946901666560
1403636946951666432
1403636947001666560
1403636947051666432
1403636947101666560
1403636947151666432
1403636947201666560
1403636947251666432
1403636947301666560
1403636947351666432
1403636947401666560
1403636947451666432
1403636947501666560
1403636947551666432
1403636947601666560
1403636947651666432
1403636947701666560
1403636947751666432
1403636947801666560
1403636947851666432
1403636947901666560
1403636947951666432
1403636948001666560
1403636948051666432
1403636948101666560
1403636948151666432
1403636948201666560
1403636948251666432
1403636948301666560
1403636948351666432
1403636948401666560
1403636948451666432
1403636948501666560
1403636948551666432
1403636948601666560
1403636948651666432
1403636948701666560
1403636948751666432
1403636948801666560
1403636948851666432
1403636948901666560
1403636948951666432
1403636949001666560
1403636949051666432
1403636949101666560
1403636949151666432
1403636949201666560
1403636949251666432
1403636949301666560
1403636949351666432
1403636949401666560
1403636949451666432
1403636949501666560
1403636949551666432
1403636949601666560
1403636949651666432
1403636949701666560
1403636949751666432
1403636949801666560
1403636949851666432
1403636949901666560
1403636949951666432
1403636950001666560
1403636950051666432
1403636950101666560
1403636950151666432
1403636950201666560
1403636950251666432
1403636950301666560
1403636950351666432
1403636950401666560
1403636950451666432
1403636950501666560
1403636950551666432
1403636950601666560
1403636950651666432
1403636950701666560
1403636950751666432
1403636950801666560
1403636950851666432
1403636950901666560
1403636950951666432
1403636951001666560
1403636951051666432
1403636951101666560
1403636951151666432
1403636951201666560
1403636951251666432
1403636951301666560
1403636951351666432
1403636951401666560
1403636951451666432
1403636951501666560
1403636951551666432
1403636951601666560
1403636951651666432
1403636951701666560
1403636951751666432
1403636951801666560
1403636951851666432
1403636951901666560
1403636951951666432
1403636952001666560
1403636952051666432
1403636952101666560
1403636952151666432
1403636952201666560
1403636952251666432
1403636952301666560
1403636952351666432
1403636952401666560
1403636952451666432
1403636952501666560
1403636952551666432
1403636952601666560
1403636952651666432
1403636952701666560
1403636952751666432
1403636952801666560
1403636952851666432
1403636952901666560
1403636952951666432
1403636953001666560
1403636953051666432
1403636953101666560
1403636953151666432
1403636953201666560
1403636953251666432
1403636953301666560
1403636953351666432
1403636953401666560
1403636953451666432
1403636953501666560
1403636953551666432
1403636953601666560
1403636953651666432
1403636953701666560
1403636953751666432
1403636953801666560
1403636953851666432
1403636953901666560
1403636953951666432
1403636954001666560
1403636954051666432
1403636954101666560
1403636954151666432
1403636954201666560
1403636954251666432
1403636954301666560
1403636954351666432
1403636954401666560
1403636954451666432
1403636954501666560
1403636954551666432
1403636954601666560
1403636954651666432
1403636954701666560
1403636954751666432
1403636954801666560
1403636954851666432
1403636954901666560
1403636954951666432
1403636955001666560
1403636955051666432
1403636955101666560
1403636955151666432
1403636955201666560
1403636955251666432
1403636955301666560
1403636955351666432
1403636955401666560
1403636955451666432
1403636955501666560
1403636955551666432
1403636955601666560
1403636955651666432
1403636955701666560
1403636955751666432
1403636955801666560
1403636955851666432
1403636955901666560
1403636955951666432
1403636956001666560
1403636956051666432
1403636956101666560
1403636956151666432
1403636956201666560
1403636956251666432
1403636956301666560
1403636956351666432
1403636956401666560
1403636956451666432
1403636956501666560
1403636956551666432
1403636956601666560
1403636956651666432
1403636956701666560
1403636956751666432
1403636956801666560
1403636956851666432
1403636956901666560
1403636956951666432
1403636957001666560
1403636957051666432
1403636957101666560
1403636957151666432
1403636957201666560
1403636957251666432
1403636957301666560
1403636957351666432
1403636957401666560
1403636957451666432
1403636957501666560
1403636957551666432
1403636957601666560
1403636957651666432
1403636957701666560
1403636957751666432
1403636957801666560
1403636957851666432
1403636957901666560
1403636957951666432
1403636958001666560
1403636958051666432
1403636958101666560
1403636958151666432
1403636958201666560
1403636958251666432
1403636958301666560
1403636958351666432
1403636958401666560
1403636958451666432
1403636958501666560
1403636958551666432
1403636958601666560
1403636958651666432
1403636958701666560
1403636958751666432
1403636958801666560
1403636958851666432
1403636958901666560
1403636958951666432
1403636959001666560
1403636959051666432
1403636959101666560
1403636959151666432
1403636959201666560
1403636959251666432
1403636959301666560
1403636959351666432
1403636959401666560
1403636959451666432
1403636959501666560
1403636959551666432
1403636959601666560
1403636959651666432
1403636959701666560
1403636959751666432
1403636959801666560
1403636959851666432
1403636959901666560
1403636959951666432
1403636960001666560
1403636960051666432
1403636960101666560
1403636960151666432
1403636960201666560
1403636960251666432
1403636960301666560
1403636960351666432
1403636960401666560
1403636960451666432
1403636960501666560
1403636960551666432
1403636960601666560
1403636960651666432
1403636960701666560
1403636960751666432
1403636960801666560
1403636960851666432
1403636960901666560
1403636960951666432
1403636961001666560
1403636961051666432
1403636961101666560
1403636961151666432
1403636961201666560
1403636961251666432
1403636961301666560
1403636961351666432
1403636961401666560
1403636961451666432
1403636961501666560
1403636961551666432
1403636961601666560
1403636961651666432
1403636961701666560
1403636961751666432
1403636961801666560
1403636961851666432
1403636961901666560
1403636961951666432
1403636962001666560
1403636962051666432
1403636962101666560
1403636962151666432
1403636962201666560
1403636962251666432
1403636962301666560
1403636962351666432
1403636962401666560
1403636962451666432
1403636962501666560
1403636962551666432
1403636962601666560
1403636962651666432
1403636962701666560
1403636962751666432
1403636962801666560
1403636962851666432
1403636962901666560
1403636962951666432
1403636963001666560
1403636963051666432
1403636963101666560
1403636963151666432
1403636963201666560
1403636963251666432
1403636963301666560
1403636963351666432
1403636963401666560
1403636963451666432
1403636963501666560
1403636963551666432
1403636963601666560
1403636963651666432
1403636963701666560
1403636963751666432
1403636963801666560
1403636963851666432
1403636963901666560
1403636963951666432
1403636964001666560
1403636964051666432
1403636964101666560
1403636964151666432
1403636964201666560
1403636964251666432
1403636964301666560
1403636964351666432
1403636964401666560
1403636964451666432
1403636964501666560
1403636964551666432
1403636964601666560
1403636964651666432
1403636964701666560
1403636964751666432
1403636964801666560
1403636964851666432
1403636964901666560
1403636964951666432
1403636965001666560
1403636965051666432
1403636965101666560
1403636965151666432
1403636965201666560
1403636965251666432
1403636965301666560
1403636965351666432
1403636965401666560
1403636965451666432
1403636965501666560
1403636965551666432
1403636965601666560
1403636965651666432
1403636965701666560
1403636965751666432
1403636965801666560
1403636965851666432
1403636965901666560
1403636965951666432
1403636966001666560
1403636966051666432
1403636966101666560
1403636966151666432
1403636966201666560
1403636966251666432
1403636966301666560
1403636966351666432
1403636966401666560
1403636966451666432
1403636966501666560
1403636966551666432
1403636966601666560
1403636966651666432
1403636966701666560
1403636966751666432
1403636966801666560
1403636966851666432
1403636966901666560
1403636966951666432
1403636967001666560
1403636967051666432
1403636967101666560
1403636967151666432
1403636967201666560
1403636967251666432
1403636967301666560
1403636967351666432
1403636967401666560
1403636967451666432
1403636967501666560
1403636967551666432
1403636967601666560
1403636967651666432
1403636967701666560
1403636967751666432
1403636967801666560
1403636967851666432
1403636967901666560
1403636967951666432
1403636968001666560
1403636968051666432
1403636968101666560
1403636968151666432
1403636968201666560
1403636968251666432
1403636968301666560
1403636968351666432
1403636968401666560
1403636968451666432
1403636968501666560
1403636968551666432
1403636968601666560
1403636968651666432
1403636968701666560
1403636968751666432
1403636968801666560
1403636968851666432
1403636968901666560
1403636968951666432
1403636969001666560
1403636969051666432
1403636969101666560
1403636969151666432
1403636969201666560
1403636969251666432
1403636969301666560
1403636969351666432
1403636969401666560
1403636969451666432
1403636969501666560
1403636969551666432
1403636969601666560
1403636969651666432
1403636969701666560
1403636969751666432
1403636969801666560
1403636969851666432
1403636969901666560
1403636969951666432
1403636970001666560
1403636970051666432
1403636970101666560
1403636970151666432
1403636970201666560
1403636970251666432
1403636970301666560
1403636970351666432
1403636970401666560
1403636970451666432
1403636970501666560
1403636970551666432
1403636970601666560
1403636970651666432
1403636970701666560
1403636970751666432
1403636970801666560
1403636970851666432
1403636970901666560
1403636970951666432
1403636971001666560
1403636971051666432
1403636971101666560
1403636971151666432
1403636971201666560
1403636971251666432
1403636971301666560
1403636971351666432
1403636971401666560
1403636971451666432
1403636971501666560
1403636971551666432
1403636971601666560
1403636971651666432
1403636971701666560
1403636971751666432
1403636971801666560
1403636971851666432
1403636971901666560
1403636971951666432
1403636972001666560
1403636972051666432
1403636972101666560
1403636972151666432
1403636972201666560
1403636972251666432
1403636972301666560
1403636972351666432
1403636972401666560
1403636972451666432
1403636972501666560
1403636972551666432
1403636972601666560
1403636972651666432
1403636972701666560
1403636972751666432
1403636972801666560
1403636972851666432
1403636972901666560
1403636972951666432
1403636973001666560
1403636973051666432
1403636973101666560
1403636973151666432
1403636973201666560
1403636973251666432
1403636973301666560
1403636973351666432
1403636973401666560
1403636973451666432
1403636973501666560
1403636973551666432
1403636973601666560
1403636973651666432
1403636973701666560
1403636973751666432
1403636973801666560
1403636973851666432
1403636973901666560
1403636973951666432
1403636974001666560
1403636974051666432
1403636974101666560
1403636974151666432
1403636974201666560
1403636974251666432
1403636974301666560
1403636974351666432
1403636974401666560
1403636974451666432
1403636974501666560
1403636974551666432
1403636974601666560
1403636974651666432
1403636974701666560
1403636974751666432
1403636974801666560
1403636974851666432
1403636974901666560
1403636974951666432
1403636975001666560
1403636975051666432
1403636975101666560
1403636975151666432
1403636975201666560
1403636975251666432
1403636975301666560
1403636975351666432
1403636975401666560
1403636975451666432
1403636975501666560
1403636975551666432
1403636975601666560
1403636975651666432
1403636975701666560
1403636975751666432
1403636975801666560
1403636975851666432
1403636975901666560
1403636975951666432
1403636976001666560
1403636976051666432
1403636976101666560
1403636976151666432
1403636976201666560
1403636976251666432
1403636976301666560
1403636976351666432
1403636976401666560
1403636976451666432
1403636976501666560
1403636976551666432
1403636976601666560
1403636976651666432
1403636976701666560
1403636976751666432
1403636976801666560
1403636976851666432
1403636976901666560
1403636976951666432
1403636977001666560
1403636977051666432
1403636977101666560
1403636977151666432
1403636977201666560
1403636977251666432
1403636977301666560
1403636977351666432
1403636977401666560
1403636977451666432
1403636977501666560
1403636977551666432
1403636977601666560
1403636977651666432
1403636977701666560
1403636977751666432
1403636977801666560
1403636977851666432
1403636977901666560
1403636977951666432
1403636978001666560
1403636978051666432
1403636978101666560
1403636978151666432
1403636978201666560
1403636978251666432
1403636978301666560
1403636978351666432
1403636978401666560
1403636978451666432
1403636978501666560
1403636978551666432
1403636978601666560
1403636978651666432
1403636978701666560
1403636978751666432
1403636978801666560
1403636978851666432
1403636978901666560
1403636978951666432
1403636979001666560
1403636979051666432
1403636979101666560
1403636979151666432
1403636979201666560
1403636979251666432
1403636979301666560
1403636979351666432
1403636979401666560
1403636979451666432
1403636979501666560
1403636979551666432
1403636979601666560
1403636979651666432
1403636979701666560
1403636979751666432
1403636979801666560
1403636979851666432
1403636979901666560
1403636979951666432
1403636980001666560
1403636980051666432
1403636980101666560
1403636980151666432
1403636980201666560
1403636980251666432
1403636980301666560
1403636980351666432
1403636980401666560
1403636980451666432
1403636980501666560
1403636980551666432
1403636980601666560
1403636980651666432
1403636980701666560
1403636980751666432
1403636980801666560
1403636980851666432
1403636980901666560
1403636980951666432
1403636981001666560
1403636981051666432
1403636981101666560
1403636981151666432
1403636981201666560
1403636981251666432
1403636981301666560
1403636981351666432
1403636981401666560
1403636981451666432
1403636981501666560
1403636981551666432
1403636981601666560
1403636981651666432
1403636981701666560
1403636981751666432
1403636981801666560
1403636981851666432
1403636981901666560
1403636981951666432
1403636982001666560
1403636982051666432
1403636982101666560
1403636982151666432
1403636982201666560
1403636982251666432
1403636982301666560
1403636982351666432
1403636982401666560
1403636982451666432
1403636982501666560
1403636982551666432
1403636982601666560
1403636982651666432
1403636982701666560
1403636982751666432
1403636982801666560
1403636982851666432
1403636982901666560
1403636982951666432
1403636983001666560
1403636983051666432
1403636983101666560
1403636983151666432
1403636983201666560
1403636983251666432
1403636983301666560
1403636983351666432
1403636983401666560
1403636983451666432
1403636983501666560
1403636983551666432
1403636983601666560
1403636983651666432
1403636983701666560
1403636983751666432
1403636983801666560
1403636983851666432
1403636983901666560
1403636983951666432
1403636984001666560
1403636984051666432
1403636984101666560
1403636984151666432
1403636984201666560
1403636984251666432
1403636984301666560
1403636984351666432
1403636984401666560
1403636984451666432
1403636984501666560
1403636984551666432
1403636984601666560
1403636984651666432
1403636984701666560
1403636984751666432
1403636984801666560
1403636984851666432
1403636984901666560
1403636984951666432
1403636985001666560
1403636985051666432
1403636985101666560
1403636985151666432
1403636985201666560
1403636985251666432
1403636985301666560
1403636985351666432
1403636985401666560
1403636985451666432
1403636985501666560
1403636985551666432
1403636985601666560
1403636985651666432
1403636985701666560
1403636985751666432
1403636985801666560
1403636985851666432
1403636985901666560
1403636985951666432
1403636986001666560
1403636986051666432
1403636986101666560
1403636986151666432
1403636986201666560
1403636986251666432
1403636986301666560
1403636986351666432
1403636986401666560
1403636986451666432
1403636986501666560
1403636986551666432
1403636986601666560
1403636986651666432
1403636986701666560
1403636986751666432
1403636986801666560
1403636986851666432
1403636986901666560
1403636986951666432
1403636987001666560
1403636987051666432
1403636987101666560
1403636987151666432
1403636987201666560
1403636987251666432
1403636987301666560
1403636987351666432
1403636987401666560
1403636987451666432
1403636987501666560
1403636987551666432
1403636987601666560
1403636987651666432
1403636987701666560
1403636987751666432
1403636987801666560
1403636987851666432
1403636987901666560
1403636987951666432
1403636988001666560
1403636988051666432
1403636988101666560
1403636988151666432
1403636988201666560
1403636988251666432
1403636988301666560
1403636988351666432
1403636988401666560
1403636988451666432
1403636988501666560
1403636988551666432
1403636988601666560
1403636988651666432
1403636988701666560
1403636988751666432
1403636988801666560
1403636988851666432
1403636988901666560
1403636988951666432
1403636989001666560
1403636989051666432
1403636989101666560
1403636989151666432
1403636989201666560
1403636989251666432
1403636989301666560
1403636989351666432
1403636989401666560
1403636989451666432
1403636989501666560
1403636989551666432
1403636989601666560
1403636989651666432
1403636989701666560
1403636989751666432
1403636989801666560
1403636989851666432
1403636989901666560
1403636989951666432
1403636990001666560
1403636990051666432
1403636990101666560
1403636990151666432
1403636990201666560
1403636990251666432
1403636990301666560
1403636990351666432
1403636990401666560
1403636990451666432
1403636990501666560
1403636990551666432
1403636990601666560
1403636990651666432
1403636990701666560
1403636990751666432
1403636990801666560
1403636990851666432
1403636990901666560
1403636990951666432
1403636991001666560
1403636991051666432
1403636991101666560
1403636991151666432
1403636991201666560
1403636991251666432
1403636991301666560
1403636991351666432
1403636991401666560
1403636991451666432
1403636991501666560
1403636991551666432
1403636991601666560
1403636991651666432
1403636991701666560
1403636991751666432
1403636991801666560
1403636991851666432
1403636991901666560
1403636991951666432
1403636992001666560
1403636992051666432
1403636992101666560
1403636992151666432
1403636992201666560
1403636992251666432
1403636992301666560
1403636992351666432
1403636992401666560
1403636992451666432
1403636992501666560
1403636992551666432
1403636992601666560
1403636992651666432
1403636992701666560
1403636992751666432
1403636992801666560
1403636992851666432
1403636992901666560
1403636992951666432
1403636993001666560
1403636993051666432
1403636993101666560
1403636993151666432
1403636993201666560
1403636993251666432
1403636993301666560
1403636993351666432
1403636993401666560
1403636993451666432
1403636993501666560
1403636993551666432
1403636993601666560
1403636993651666432
1403636993701666560
1403636993751666432
1403636993801666560
1403636993851666432
1403636993901666560
1403636993951666432
1403636994001666560
1403636994051666432
1403636994101666560
1403636994151666432
1403636994201666560
1403636994251666432
1403636994301666560
1403636994351666432
1403636994401666560
1403636994451666432
1403636994501666560
1403636994551666432
1403636994601666560
1403636994651666432
1403636994701666560
1403636994751666432
1403636994801666560
1403636994851666432
1403636994901666560
1403636994951666432
1403636995001666560
1403636995051666432
1403636995101666560
1403636995151666432
1403636995201666560
1403636995251666432
1403636995301666560
1403636995351666432
1403636995401666560
1403636995451666432
1403636995501666560
1403636995551666432
1403636995601666560
1403636995651666432
1403636995701666560
1403636995751666432
1403636995801666560
1403636995851666432
1403636995901666560
1403636995951666432
1403636996001666560
1403636996051666432
1403636996101666560
1403636996151666432
1403636996201666560
1403636996251666432
1403636996301666560
1403636996351666432
1403636996401666560
1403636996451666432
1403636996501666560
1403636996551666432
1403636996601666560
1403636996651666432
1403636996701666560
1403636996751666432
1403636996801666560
1403636996851666432
1403636996901666560
1403636996951666432
1403636997001666560
1403636997051666432
1403636997101666560
1403636997151666432
1403636997201666560
1403636997251666432
1403636997301666560
1403636997351666432
1403636997401666560
1403636997451666432
1403636997501666560
1403636997551666432
1403636997601666560
1403636997651666432
1403636997701666560
1403636997751666432
1403636997801666560
1403636997851666432
1403636997901666560
1403636997951666432
1403636998001666560
1403636998051666432
1403636998101666560
1403636998151666432
1403636998201666560
1403636998251666432
1403636998301666560
1403636998351666432
1403636998401666560
1403636998451666432
1403636998501666560
1403636998551666432
1403636998601666560
1403636998651666432
1403636998701666560
1403636998751666432
1403636998801666560
1403636998851666432
1403636998901666560
1403636998951666432
1403636999001666560
1403636999051666432
1403636999101666560
1403636999151666432
1403636999201666560
1403636999251666432
1403636999301666560
1403636999351666432
1403636999401666560
1403636999451666432
1403636999501666560
1403636999551666432
1403636999601666560
1403636999651666432
1403636999701666560
1403636999751666432
1403636999801666560
1403636999851666432
1403636999901666560
1403636999951666432
1403637000001666560
1403637000051666432
1403637000101666560
1403637000151666432
1403637000201666560
1403637000251666432
1403637000301666560
1403637000351666432
1403637000401666560
1403637000451666432
1403637000501666560
1403637000551666432
1403637000601666560
1403637000651666432
1403637000701666560
1403637000751666432
1403637000801666560
1403637000851666432
1403637000901666560
1403637000951666432
1403637001001666560
1403637001051666432
1403637001101666560
1403637001151666432
1403637001201666560
1403637001251666432
1403637001301666560
1403637001351666432
1403637001401666560
1403637001451666432
1403637001501666560
1403637001551666432
1403637001601666560
1403637001651666432
1403637001701666560
1403637001751666432
1403637001801666560
1403637001851666432
1403637001901666560
1403637001951666432
1403637002001666560
1403637002051666432
1403637002101666560
1403637002151666432
1403637002201666560
1403637002251666432
1403637002301666560
1403637002351666432
1403637002401666560
1403637002451666432
1403637002501666560
1403637002551666432
1403637002601666560
1403637002651666432
1403637002701666560
1403637002751666432
1403637002801666560
1403637002851666432
1403637002901666560
1403637002951666432
1403637003001666560
1403637003051666432
1403637003101666560
1403637003151666432
1403637003201666560
1403637003251666432
1403637003301666560
1403637003351666432
1403637003401666560
1403637003451666432
1403637003501666560
1403637003551666432
1403637003601666560
1403637003651666432
1403637003701666560
1403637003751666432
1403637003801666560
1403637003851666432
1403637003901666560
1403637003951666432
1403637004001666560
1403637004051666432
1403637004101666560
1403637004151666432
1403637004201666560
1403637004251666432
1403637004301666560
1403637004351666432
1403637004401666560
1403637004451666432
1403637004501666560
1403637004551666432
1403637004601666560
1403637004651666432
1403637004701666560
1403637004751666432
1403637004801666560
1403637004851666432
1403637004901666560
1403637004951666432
1403637005001666560
1403637005051666432
1403637005101666560
1403637005151666432
1403637005201666560
1403637005251666432
1403637005301666560
1403637005351666432
1403637005401666560
1403637005451666432
1403637005501666560
1403637005551666432
1403637005601666560
1403637005651666432
1403637005701666560
1403637005751666432
1403637005801666560
1403637005851666432
1403637005901666560
1403637005951666432
1403637006001666560
1403637006051666432
1403637006101666560
1403637006151666432
1403637006201666560
1403637006251666432
1403637006301666560
1403637006351666432
1403637006401666560
1403637006451666432
1403637006501666560
1403637006551666432
1403637006601666560
1403637006651666432
1403637006701666560
1403637006751666432
1403637006801666560
1403637006851666432
1403637006901666560
1403637006951666432
1403637007001666560
1403637007051666432
1403637007101666560
1403637007151666432
1403637007201666560
1403637007251666432
1403637007301666560
1403637007351666432
1403637007401666560
1403637007451666432
1403637007501666560
1403637007551666432
1403637007601666560
1403637007651666432
1403637007701666560
1403637007751666432
1403637007801666560
1403637007851666432
1403637007901666560
1403637007951666432
1403637008001666560
1403637008051666432
1403637008101666560
1403637008151666432
1403637008201666560
1403637008251666432
1403637008301666560
1403637008351666432
1403637008401666560
1403637008451666432
1403637008501666560
1403637008551666432
1403637008601666560
1403637008651666432
1403637008701666560
1403637008751666432
1403637008801666560
1403637008851666432
1403637008901666560
1403637008951666432
1403637009001666560
1403637009051666432
1403637009101666560
1403637009151666432
1403637009201666560
1403637009251666432
1403637009301666560
1403637009351666432
1403637009401666560
1403637009451666432
1403637009501666560
1403637009551666432
1403637009601666560
1403637009651666432
1403637009701666560
1403637009751666432
1403637009801666560
1403637009851666432
1403637009901666560
1403637009951666432
1403637010001666560
1403637010051666432
1403637010101666560
1403637010151666432
1403637010201666560
1403637010251666432
1403637010301666560
1403637010351666432
1403637010401666560
1403637010451666432
1403637010501666560
1403637010551666432
1403637010601666560
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/MH03.txt
================================================
1403637130538319104
1403637130588318976
1403637130638319104
1403637130688318976
1403637130738319104
1403637130788318976
1403637130838319104
1403637130888318976
1403637130938319104
1403637130988318976
1403637131038319104
1403637131088318976
1403637131138319104
1403637131188318976
1403637131238319104
1403637131288318976
1403637131338319104
1403637131388318976
1403637131438319104
1403637131488318976
1403637131538319104
1403637131588318976
1403637131638319104
1403637131688318976
1403637131738319104
1403637131788318976
1403637131838319104
1403637131888318976
1403637131938319104
1403637131988318976
1403637132038319104
1403637132088318976
1403637132138319104
1403637132188318976
1403637132238319104
1403637132288318976
1403637132338319104
1403637132388318976
1403637132438319104
1403637132488318976
1403637132538319104
1403637132588318976
1403637132638319104
1403637132688318976
1403637132738319104
1403637132788318976
1403637132838319104
1403637132888318976
1403637132938319104
1403637132988318976
1403637133038319104
1403637133088318976
1403637133138319104
1403637133188318976
1403637133238319104
1403637133288318976
1403637133338319104
1403637133388318976
1403637133438319104
1403637133488318976
1403637133538319104
1403637133588318976
1403637133638319104
1403637133688318976
1403637133738319104
1403637133788318976
1403637133838319104
1403637133888318976
1403637133938319104
1403637133988318976
1403637134038319104
1403637134088318976
1403637134138319104
1403637134188318976
1403637134238319104
1403637134288318976
1403637134338319104
1403637134388318976
1403637134438319104
1403637134488318976
1403637134538319104
1403637134588318976
1403637134638319104
1403637134688318976
1403637134738319104
1403637134788318976
1403637134838319104
1403637134888318976
1403637134938319104
1403637134988318976
1403637135038319104
1403637135088318976
1403637135138319104
1403637135188318976
1403637135238319104
1403637135288318976
1403637135338319104
1403637135388318976
1403637135438319104
1403637135488318976
1403637135538319104
1403637135588318976
1403637135638319104
1403637135688318976
1403637135738319104
1403637135788318976
1403637135838319104
1403637135888318976
1403637135938319104
1403637135988318976
1403637136038319104
1403637136088318976
1403637136138319104
1403637136188318976
1403637136238319104
1403637136288318976
1403637136338319104
1403637136388318976
1403637136438319104
1403637136488318976
1403637136538319104
1403637136588318976
1403637136638319104
1403637136688318976
1403637136738319104
1403637136788318976
1403637136838319104
1403637136888318976
1403637136938319104
1403637136988318976
1403637137038319104
1403637137088318976
1403637137138319104
1403637137188318976
1403637137238319104
1403637137288318976
1403637137338319104
1403637137388318976
1403637137438319104
1403637137488318976
1403637137538319104
1403637137588318976
1403637137638319104
1403637137688318976
1403637137738319104
1403637137788318976
1403637137838319104
1403637137888318976
1403637137938319104
1403637137988318976
1403637138038319104
1403637138088318976
1403637138138319104
1403637138188318976
1403637138238319104
1403637138288318976
1403637138338319104
1403637138388318976
1403637138438319104
1403637138488318976
1403637138538319104
1403637138588318976
1403637138638319104
1403637138688318976
1403637138738319104
1403637138788318976
1403637138838319104
1403637138888318976
1403637138938319104
1403637138988318976
1403637139038319104
1403637139088318976
1403637139138319104
1403637139188318976
1403637139238319104
1403637139288318976
1403637139338319104
1403637139388318976
1403637139438319104
1403637139488318976
1403637139538319104
1403637139588318976
1403637139638319104
1403637139688318976
1403637139738319104
1403637139788318976
1403637139838319104
1403637139888318976
1403637139938319104
1403637139988318976
1403637140038319104
1403637140088318976
1403637140138319104
1403637140188318976
1403637140238319104
1403637140288318976
1403637140338319104
1403637140388318976
1403637140438319104
1403637140488318976
1403637140538319104
1403637140588318976
1403637140638319104
1403637140688318976
1403637140738319104
1403637140788318976
1403637140838319104
1403637140888318976
1403637140938319104
1403637140988318976
1403637141038319104
1403637141088318976
1403637141138319104
1403637141188318976
1403637141238319104
1403637141288318976
1403637141338319104
1403637141388318976
1403637141438319104
1403637141488318976
1403637141538319104
1403637141588318976
1403637141638319104
1403637141688318976
1403637141738319104
1403637141788318976
1403637141838319104
1403637141888318976
1403637141938319104
1403637141988318976
1403637142038319104
1403637142088318976
1403637142138319104
1403637142188318976
1403637142238319104
1403637142288318976
1403637142338319104
1403637142388318976
1403637142438319104
1403637142488318976
1403637142538319104
1403637142588318976
1403637142638319104
1403637142688318976
1403637142738319104
1403637142788318976
1403637142838319104
1403637142888318976
1403637142938319104
1403637142988318976
1403637143038319104
1403637143088318976
1403637143138319104
1403637143188318976
1403637143238319104
1403637143288318976
1403637143338319104
1403637143388318976
1403637143438319104
1403637143488318976
1403637143538319104
1403637143588318976
1403637143638319104
1403637143688318976
1403637143738319104
1403637143788318976
1403637143838319104
1403637143888318976
1403637143938319104
1403637143988318976
1403637144038319104
1403637144088318976
1403637144138319104
1403637144188318976
1403637144238319104
1403637144288318976
1403637144338319104
1403637144388318976
1403637144438319104
1403637144488318976
1403637144538319104
1403637144588318976
1403637144638319104
1403637144688318976
1403637144738319104
1403637144788318976
1403637144838319104
1403637144888318976
1403637144938319104
1403637144988318976
1403637145038319104
1403637145088318976
1403637145138319104
1403637145188318976
1403637145238319104
1403637145288318976
1403637145338319104
1403637145388318976
1403637145438319104
1403637145488318976
1403637145538319104
1403637145588318976
1403637145638319104
1403637145688318976
1403637145738319104
1403637145788318976
1403637145838319104
1403637145888318976
1403637145938319104
1403637145988318976
1403637146038319104
1403637146088318976
1403637146138319104
1403637146188318976
1403637146238319104
1403637146288318976
1403637146338319104
1403637146388318976
1403637146438319104
1403637146488318976
1403637146538319104
1403637146588318976
1403637146638319104
1403637146688318976
1403637146738319104
1403637146788318976
1403637146838319104
1403637146888318976
1403637146938319104
1403637146988318976
1403637147038319104
1403637147088318976
1403637147138319104
1403637147188318976
1403637147238319104
1403637147288318976
1403637147338319104
1403637147388318976
1403637147438319104
1403637147488318976
1403637147538319104
1403637147588318976
1403637147638319104
1403637147688318976
1403637147738319104
1403637147788318976
1403637147838319104
1403637147888318976
1403637147938319104
1403637147988318976
1403637148038319104
1403637148088318976
1403637148138319104
1403637148188318976
1403637148238319104
1403637148288318976
1403637148338319104
1403637148388318976
1403637148438319104
1403637148488318976
1403637148538319104
1403637148588318976
1403637148638319104
1403637148688318976
1403637148738319104
1403637148788318976
1403637148838319104
1403637148888318976
1403637148938319104
1403637148988318976
1403637149038319104
1403637149088318976
1403637149138319104
1403637149188318976
1403637149238319104
1403637149288318976
1403637149338319104
1403637149388318976
1403637149438319104
1403637149488318976
1403637149538319104
1403637149588318976
1403637149638319104
1403637149688318976
1403637149738319104
1403637149788318976
1403637149838319104
1403637149888318976
1403637149938319104
1403637149988318976
1403637150038319104
1403637150088318976
1403637150138319104
1403637150188318976
1403637150238319104
1403637150288318976
1403637150338319104
1403637150388318976
1403637150438319104
1403637150488318976
1403637150538319104
1403637150588318976
1403637150638319104
1403637150688318976
1403637150738319104
1403637150788318976
1403637150838319104
1403637150888318976
1403637150938319104
1403637150988318976
1403637151038319104
1403637151088318976
1403637151138319104
1403637151188318976
1403637151238319104
1403637151288318976
1403637151338319104
1403637151388318976
1403637151438319104
1403637151488318976
1403637151538319104
1403637151588318976
1403637151638319104
1403637151688318976
1403637151738319104
1403637151788318976
1403637151838319104
1403637151888318976
1403637151938319104
1403637151988318976
1403637152038319104
1403637152088318976
1403637152138319104
1403637152188318976
1403637152238319104
1403637152288318976
1403637152338319104
1403637152388318976
1403637152438319104
1403637152488318976
1403637152538319104
1403637152588318976
1403637152638319104
1403637152688318976
1403637152738319104
1403637152788318976
1403637152838319104
1403637152888318976
1403637152938319104
1403637152988318976
1403637153038319104
1403637153088318976
1403637153138319104
1403637153188318976
1403637153238319104
1403637153288318976
1403637153338319104
1403637153388318976
1403637153438319104
1403637153488318976
1403637153538319104
1403637153588318976
1403637153638319104
1403637153688318976
1403637153738319104
1403637153788318976
1403637153838319104
1403637153888318976
1403637153938319104
1403637153988318976
1403637154038319104
1403637154088318976
1403637154138319104
1403637154188318976
1403637154238319104
1403637154288318976
1403637154338319104
1403637154388318976
1403637154438319104
1403637154488318976
1403637154538319104
1403637154588318976
1403637154638319104
1403637154688318976
1403637154738319104
1403637154788318976
1403637154838319104
1403637154888318976
1403637154938319104
1403637154988318976
1403637155038319104
1403637155088318976
1403637155138319104
1403637155188318976
1403637155238319104
1403637155288318976
1403637155338319104
1403637155388318976
1403637155438319104
1403637155488318976
1403637155538319104
1403637155588318976
1403637155638319104
1403637155688318976
1403637155738319104
1403637155788318976
1403637155838319104
1403637155888318976
1403637155938319104
1403637155988318976
1403637156038319104
1403637156088318976
1403637156138319104
1403637156188318976
1403637156238319104
1403637156288318976
1403637156338319104
1403637156388318976
1403637156438319104
1403637156488318976
1403637156538319104
1403637156588318976
1403637156638319104
1403637156688318976
1403637156738319104
1403637156788318976
1403637156838319104
1403637156888318976
1403637156938319104
1403637156988318976
1403637157038319104
1403637157088318976
1403637157138319104
1403637157188318976
1403637157238319104
1403637157288318976
1403637157338319104
1403637157388318976
1403637157438319104
1403637157488318976
1403637157538319104
1403637157588318976
1403637157638319104
1403637157688318976
1403637157738319104
1403637157788318976
1403637157838319104
1403637157888318976
1403637157938319104
1403637157988318976
1403637158038319104
1403637158088318976
1403637158138319104
1403637158188318976
1403637158238319104
1403637158288318976
1403637158338319104
1403637158388318976
1403637158438319104
1403637158488318976
1403637158538319104
1403637158588318976
1403637158638319104
1403637158688318976
1403637158738319104
1403637158788318976
1403637158838319104
1403637158888318976
1403637158938319104
1403637158988318976
1403637159038319104
1403637159088318976
1403637159138319104
1403637159188318976
1403637159238319104
1403637159288318976
1403637159338319104
1403637159388318976
1403637159438319104
1403637159488318976
1403637159538319104
1403637159588318976
1403637159638319104
1403637159688318976
1403637159738319104
1403637159788318976
1403637159838319104
1403637159888318976
1403637159938319104
1403637159988318976
1403637160038319104
1403637160088318976
1403637160138319104
1403637160188318976
1403637160238319104
1403637160288318976
1403637160338319104
1403637160388318976
1403637160438319104
1403637160488318976
1403637160538319104
1403637160588318976
1403637160638319104
1403637160688318976
1403637160738319104
1403637160788318976
1403637160838319104
1403637160888318976
1403637160938319104
1403637160988318976
1403637161038319104
1403637161088318976
1403637161138319104
1403637161188318976
1403637161238319104
1403637161288318976
1403637161338319104
1403637161388318976
1403637161438319104
1403637161488318976
1403637161538319104
1403637161588318976
1403637161638319104
1403637161688318976
1403637161738319104
1403637161788318976
1403637161838319104
1403637161888318976
1403637161938319104
1403637161988318976
1403637162038319104
1403637162088318976
1403637162138319104
1403637162188318976
1403637162238319104
1403637162288318976
1403637162338319104
1403637162388318976
1403637162438319104
1403637162488318976
1403637162538319104
1403637162588318976
1403637162638319104
1403637162688318976
1403637162738319104
1403637162788318976
1403637162838319104
1403637162888318976
1403637162938319104
1403637162988318976
1403637163038319104
1403637163088318976
1403637163138319104
1403637163188318976
1403637163238319104
1403637163288318976
1403637163338319104
1403637163388318976
1403637163438319104
1403637163488318976
1403637163538319104
1403637163588318976
1403637163638319104
1403637163688318976
1403637163738319104
1403637163788318976
1403637163838319104
1403637163888318976
1403637163938319104
1403637163988318976
1403637164038319104
1403637164088318976
1403637164138319104
1403637164188318976
1403637164238319104
1403637164288318976
1403637164338319104
1403637164388318976
1403637164438319104
1403637164488318976
1403637164538319104
1403637164588318976
1403637164638319104
1403637164688318976
1403637164738319104
1403637164788318976
1403637164838319104
1403637164888318976
1403637164938319104
1403637164988318976
1403637165038319104
1403637165088318976
1403637165138319104
1403637165188318976
1403637165238319104
1403637165288318976
1403637165338319104
1403637165388318976
1403637165438319104
1403637165488318976
1403637165538319104
1403637165588318976
1403637165638319104
1403637165688318976
1403637165738319104
1403637165788318976
1403637165838319104
1403637165888318976
1403637165938319104
1403637165988318976
1403637166038319104
1403637166088318976
1403637166138319104
1403637166188318976
1403637166238319104
1403637166288318976
1403637166338319104
1403637166388318976
1403637166438319104
1403637166488318976
1403637166538319104
1403637166588318976
1403637166638319104
1403637166688318976
1403637166738319104
1403637166788318976
1403637166838319104
1403637166888318976
1403637166938319104
1403637166988318976
1403637167038319104
1403637167088318976
1403637167138319104
1403637167188318976
1403637167238319104
1403637167288318976
1403637167338319104
1403637167388318976
1403637167438319104
1403637167488318976
1403637167538319104
1403637167588318976
1403637167638319104
1403637167688318976
1403637167738319104
1403637167788318976
1403637167838319104
1403637167888318976
1403637167938319104
1403637167988318976
1403637168038319104
1403637168088318976
1403637168138319104
1403637168188318976
1403637168238319104
1403637168288318976
1403637168338319104
1403637168388318976
1403637168438319104
1403637168488318976
1403637168538319104
1403637168588318976
1403637168638319104
1403637168688318976
1403637168738319104
1403637168788318976
1403637168838319104
1403637168888318976
1403637168938319104
1403637168988318976
1403637169038319104
1403637169088318976
1403637169138319104
1403637169188318976
1403637169238319104
1403637169288318976
1403637169338319104
1403637169388318976
1403637169438319104
1403637169488318976
1403637169538319104
1403637169588318976
1403637169638319104
1403637169688318976
1403637169738319104
1403637169788318976
1403637169838319104
1403637169888318976
1403637169938319104
1403637169988318976
1403637170038319104
1403637170088318976
1403637170138319104
1403637170188318976
1403637170238319104
1403637170288318976
1403637170338319104
1403637170388318976
1403637170438319104
1403637170488318976
1403637170538319104
1403637170588318976
1403637170638319104
1403637170688318976
1403637170738319104
1403637170788318976
1403637170838319104
1403637170888318976
1403637170938319104
1403637170988318976
1403637171038319104
1403637171088318976
1403637171138319104
1403637171188318976
1403637171238319104
1403637171288318976
1403637171338319104
1403637171388318976
1403637171438319104
1403637171488318976
1403637171538319104
1403637171588318976
1403637171638319104
1403637171688318976
1403637171738319104
1403637171788318976
1403637171838319104
1403637171888318976
1403637171938319104
1403637171988318976
1403637172038319104
1403637172088318976
1403637172138319104
1403637172188318976
1403637172238319104
1403637172288318976
1403637172338319104
1403637172388318976
1403637172438319104
1403637172488318976
1403637172538319104
1403637172588318976
1403637172638319104
1403637172688318976
1403637172738319104
1403637172788318976
1403637172838319104
1403637172888318976
1403637172938319104
1403637172988318976
1403637173038319104
1403637173088318976
1403637173138319104
1403637173188318976
1403637173238319104
1403637173288318976
1403637173338319104
1403637173388318976
1403637173438319104
1403637173488318976
1403637173538319104
1403637173588318976
1403637173638319104
1403637173688318976
1403637173738319104
1403637173788318976
1403637173838319104
1403637173888318976
1403637173938319104
1403637173988318976
1403637174038319104
1403637174088318976
1403637174138319104
1403637174188318976
1403637174238319104
1403637174288318976
1403637174338319104
1403637174388318976
1403637174438319104
1403637174488318976
1403637174538319104
1403637174588318976
1403637174638319104
1403637174688318976
1403637174738319104
1403637174788318976
1403637174838319104
1403637174888318976
1403637174938319104
1403637174988318976
1403637175038319104
1403637175088318976
1403637175138319104
1403637175188318976
1403637175238319104
1403637175288318976
1403637175338319104
1403637175388318976
1403637175438319104
1403637175488318976
1403637175538319104
1403637175588318976
1403637175638319104
1403637175688318976
1403637175738319104
1403637175788318976
1403637175838319104
1403637175888318976
1403637175938319104
1403637175988318976
1403637176038319104
1403637176088318976
1403637176138319104
1403637176188318976
1403637176238319104
1403637176288318976
1403637176338319104
1403637176388318976
1403637176438319104
1403637176488318976
1403637176538319104
1403637176588318976
1403637176638319104
1403637176688318976
1403637176738319104
1403637176788318976
1403637176838319104
1403637176888318976
1403637176938319104
1403637176988318976
1403637177038319104
1403637177088318976
1403637177138319104
1403637177188318976
1403637177238319104
1403637177288318976
1403637177338319104
1403637177388318976
1403637177438319104
1403637177488318976
1403637177538319104
1403637177588318976
1403637177638319104
1403637177688318976
1403637177738319104
1403637177788318976
1403637177838319104
1403637177888318976
1403637177938319104
1403637177988318976
1403637178038319104
1403637178088318976
1403637178138319104
1403637178188318976
1403637178238319104
1403637178288318976
1403637178338319104
1403637178388318976
1403637178438319104
1403637178488318976
1403637178538319104
1403637178588318976
1403637178638319104
1403637178688318976
1403637178738319104
1403637178788318976
1403637178838319104
1403637178888318976
1403637178938319104
1403637178988318976
1403637179038319104
1403637179088318976
1403637179138319104
1403637179188318976
1403637179238319104
1403637179288318976
1403637179338319104
1403637179388318976
1403637179438319104
1403637179488318976
1403637179538319104
1403637179588318976
1403637179638319104
1403637179688318976
1403637179738319104
1403637179788318976
1403637179838319104
1403637179888318976
1403637179938319104
1403637179988318976
1403637180038319104
1403637180088318976
1403637180138319104
1403637180188318976
1403637180238319104
1403637180288318976
1403637180338319104
1403637180388318976
1403637180438319104
1403637180488318976
1403637180538319104
1403637180588318976
1403637180638319104
1403637180688318976
1403637180738319104
1403637180788318976
1403637180838319104
1403637180888318976
1403637180938319104
1403637180988318976
1403637181038319104
1403637181088318976
1403637181138319104
1403637181188318976
1403637181238319104
1403637181288318976
1403637181338319104
1403637181388318976
1403637181438319104
1403637181488318976
1403637181538319104
1403637181588318976
1403637181638319104
1403637181688318976
1403637181738319104
1403637181788318976
1403637181838319104
1403637181888318976
1403637181938319104
1403637181988318976
1403637182038319104
1403637182088318976
1403637182138319104
1403637182188318976
1403637182238319104
1403637182288318976
1403637182338319104
1403637182388318976
1403637182438319104
1403637182488318976
1403637182538319104
1403637182588318976
1403637182638319104
1403637182688318976
1403637182738319104
1403637182788318976
1403637182838319104
1403637182888318976
1403637182938319104
1403637182988318976
1403637183038319104
1403637183088318976
1403637183138319104
1403637183188318976
1403637183238319104
1403637183288318976
1403637183338319104
1403637183388318976
1403637183438319104
1403637183488318976
1403637183538319104
1403637183588318976
1403637183638319104
1403637183688318976
1403637183738319104
1403637183788318976
1403637183838319104
1403637183888318976
1403637183938319104
1403637183988318976
1403637184038319104
1403637184088318976
1403637184138319104
1403637184188318976
1403637184238319104
1403637184288318976
1403637184338319104
1403637184388318976
1403637184438319104
1403637184488318976
1403637184538319104
1403637184588318976
1403637184638319104
1403637184688318976
1403637184738319104
1403637184788318976
1403637184838319104
1403637184888318976
1403637184938319104
1403637184988318976
1403637185038319104
1403637185088318976
1403637185138319104
1403637185188318976
1403637185238319104
1403637185288318976
1403637185338319104
1403637185388318976
1403637185438319104
1403637185488318976
1403637185538319104
1403637185588318976
1403637185638319104
1403637185688318976
1403637185738319104
1403637185788318976
1403637185838319104
1403637185888318976
1403637185938319104
1403637185988318976
1403637186038319104
1403637186088318976
1403637186138319104
1403637186188318976
1403637186238319104
1403637186288318976
1403637186338319104
1403637186388318976
1403637186438319104
1403637186488318976
1403637186538319104
1403637186588318976
1403637186638319104
1403637186688318976
1403637186738319104
1403637186788318976
1403637186838319104
1403637186888318976
1403637186938319104
1403637186988318976
1403637187038319104
1403637187088318976
1403637187138319104
1403637187188318976
1403637187238319104
1403637187288318976
1403637187338319104
1403637187388318976
1403637187438319104
1403637187488318976
1403637187538319104
1403637187588318976
1403637187638319104
1403637187688318976
1403637187738319104
1403637187788318976
1403637187838319104
1403637187888318976
1403637187938319104
1403637187988318976
1403637188038319104
1403637188088318976
1403637188138319104
1403637188188318976
1403637188238319104
1403637188288318976
1403637188338319104
1403637188388318976
1403637188438319104
1403637188488318976
1403637188538319104
1403637188588318976
1403637188638319104
1403637188688318976
1403637188738319104
1403637188788318976
1403637188838319104
1403637188888318976
1403637188938319104
1403637188988318976
1403637189038319104
1403637189088318976
1403637189138319104
1403637189188318976
1403637189238319104
1403637189288318976
1403637189338319104
1403637189388318976
1403637189438319104
1403637189488318976
1403637189538319104
1403637189588318976
1403637189638319104
1403637189688318976
1403637189738319104
1403637189788318976
1403637189838319104
1403637189888318976
1403637189938319104
1403637189988318976
1403637190038319104
1403637190088318976
1403637190138319104
1403637190188318976
1403637190238319104
1403637190288318976
1403637190338319104
1403637190388318976
1403637190438319104
1403637190488318976
1403637190538319104
1403637190588318976
1403637190638319104
1403637190688318976
1403637190738319104
1403637190788318976
1403637190838319104
1403637190888318976
1403637190938319104
1403637190988318976
1403637191038319104
1403637191088318976
1403637191138319104
1403637191188318976
1403637191238319104
1403637191288318976
1403637191338319104
1403637191388318976
1403637191438319104
1403637191488318976
1403637191538319104
1403637191588318976
1403637191638319104
1403637191688318976
1403637191738319104
1403637191788318976
1403637191838319104
1403637191888318976
1403637191938319104
1403637191988318976
1403637192038319104
1403637192088318976
1403637192138319104
1403637192188318976
1403637192238319104
1403637192288318976
1403637192338319104
1403637192388318976
1403637192438319104
1403637192488318976
1403637192538319104
1403637192588318976
1403637192638319104
1403637192688318976
1403637192738319104
1403637192788318976
1403637192838319104
1403637192888318976
1403637192938319104
1403637192988318976
1403637193038319104
1403637193088318976
1403637193138319104
1403637193188318976
1403637193238319104
1403637193288318976
1403637193338319104
1403637193388318976
1403637193438319104
1403637193488318976
1403637193538319104
1403637193588318976
1403637193638319104
1403637193688318976
1403637193738319104
1403637193788318976
1403637193838319104
1403637193888318976
1403637193938319104
1403637193988318976
1403637194038319104
1403637194088318976
1403637194138319104
1403637194188318976
1403637194238319104
1403637194288318976
1403637194338319104
1403637194388318976
1403637194438319104
1403637194488318976
1403637194538319104
1403637194588318976
1403637194638319104
1403637194688318976
1403637194738319104
1403637194788318976
1403637194838319104
1403637194888318976
1403637194938319104
1403637194988318976
1403637195038319104
1403637195088318976
1403637195138319104
1403637195188318976
1403637195238319104
1403637195288318976
1403637195338319104
1403637195388318976
1403637195438319104
1403637195488318976
1403637195538319104
1403637195588318976
1403637195638319104
1403637195688318976
1403637195738319104
1403637195788318976
1403637195838319104
1403637195888318976
1403637195938319104
1403637195988318976
1403637196038319104
1403637196088318976
1403637196138319104
1403637196188318976
1403637196238319104
1403637196288318976
1403637196338319104
1403637196388318976
1403637196438319104
1403637196488318976
1403637196538319104
1403637196588318976
1403637196638319104
1403637196688318976
1403637196738319104
1403637196788318976
1403637196838319104
1403637196888318976
1403637196938319104
1403637196988318976
1403637197038319104
1403637197088318976
1403637197138319104
1403637197188318976
1403637197238319104
1403637197288318976
1403637197338319104
1403637197388318976
1403637197438319104
1403637197488318976
1403637197538319104
1403637197588318976
1403637197638319104
1403637197688318976
1403637197738319104
1403637197788318976
1403637197838319104
1403637197888318976
1403637197938319104
1403637197988318976
1403637198038319104
1403637198088318976
1403637198138319104
1403637198188318976
1403637198238319104
1403637198288318976
1403637198338319104
1403637198388318976
1403637198438319104
1403637198488318976
1403637198538319104
1403637198588318976
1403637198638319104
1403637198688318976
1403637198738319104
1403637198788318976
1403637198838319104
1403637198888318976
1403637198938319104
1403637198988318976
1403637199038319104
1403637199088318976
1403637199138319104
1403637199188318976
1403637199238319104
1403637199288318976
1403637199338319104
1403637199388318976
1403637199438319104
1403637199488318976
1403637199538319104
1403637199588318976
1403637199638319104
1403637199688318976
1403637199738319104
1403637199788318976
1403637199838319104
1403637199888318976
1403637199938319104
1403637199988318976
1403637200038319104
1403637200088318976
1403637200138319104
1403637200188318976
1403637200238319104
1403637200288318976
1403637200338319104
1403637200388318976
1403637200438319104
1403637200488318976
1403637200538319104
1403637200588318976
1403637200638319104
1403637200688318976
1403637200738319104
1403637200788318976
1403637200838319104
1403637200888318976
1403637200938319104
1403637200988318976
1403637201038319104
1403637201088318976
1403637201138319104
1403637201188318976
1403637201238319104
1403637201288318976
1403637201338319104
1403637201388318976
1403637201438319104
1403637201488318976
1403637201538319104
1403637201588318976
1403637201638319104
1403637201688318976
1403637201738319104
1403637201788318976
1403637201838319104
1403637201888318976
1403637201938319104
1403637201988318976
1403637202038319104
1403637202088318976
1403637202138319104
1403637202188318976
1403637202238319104
1403637202288318976
1403637202338319104
1403637202388318976
1403637202438319104
1403637202488318976
1403637202538319104
1403637202588318976
1403637202638319104
1403637202688318976
1403637202738319104
1403637202788318976
1403637202838319104
1403637202888318976
1403637202938319104
1403637202988318976
1403637203038319104
1403637203088318976
1403637203138319104
1403637203188318976
1403637203238319104
1403637203288318976
1403637203338319104
1403637203388318976
1403637203438319104
1403637203488318976
1403637203538319104
1403637203588318976
1403637203638319104
1403637203688318976
1403637203738319104
1403637203788318976
1403637203838319104
1403637203888318976
1403637203938319104
1403637203988318976
1403637204038319104
1403637204088318976
1403637204138319104
1403637204188318976
1403637204238319104
1403637204288318976
1403637204338319104
1403637204388318976
1403637204438319104
1403637204488318976
1403637204538319104
1403637204588318976
1403637204638319104
1403637204688318976
1403637204738319104
1403637204788318976
1403637204838319104
1403637204888318976
1403637204938319104
1403637204988318976
1403637205038319104
1403637205088318976
1403637205138319104
1403637205188318976
1403637205238319104
1403637205288318976
1403637205338319104
1403637205388318976
1403637205438319104
1403637205488318976
1403637205538319104
1403637205588318976
1403637205638319104
1403637205688318976
1403637205738319104
1403637205788318976
1403637205838319104
1403637205888318976
1403637205938319104
1403637205988318976
1403637206038319104
1403637206088318976
1403637206138319104
1403637206188318976
1403637206238319104
1403637206288318976
1403637206338319104
1403637206388318976
1403637206438319104
1403637206488318976
1403637206538319104
1403637206588318976
1403637206638319104
1403637206688318976
1403637206738319104
1403637206788318976
1403637206838319104
1403637206888318976
1403637206938319104
1403637206988318976
1403637207038319104
1403637207088318976
1403637207138319104
1403637207188318976
1403637207238319104
1403637207288318976
1403637207338319104
1403637207388318976
1403637207438319104
1403637207488318976
1403637207538319104
1403637207588318976
1403637207638319104
1403637207688318976
1403637207738319104
1403637207788318976
1403637207838319104
1403637207888318976
1403637207938319104
1403637207988318976
1403637208038319104
1403637208088318976
1403637208138319104
1403637208188318976
1403637208238319104
1403637208288318976
1403637208338319104
1403637208388318976
1403637208438319104
1403637208488318976
1403637208538319104
1403637208588318976
1403637208638319104
1403637208688318976
1403637208738319104
1403637208788318976
1403637208838319104
1403637208888318976
1403637208938319104
1403637208988318976
1403637209038319104
1403637209088318976
1403637209138319104
1403637209188318976
1403637209238319104
1403637209288318976
1403637209338319104
1403637209388318976
1403637209438319104
1403637209488318976
1403637209538319104
1403637209588318976
1403637209638319104
1403637209688318976
1403637209738319104
1403637209788318976
1403637209838319104
1403637209888318976
1403637209938319104
1403637209988318976
1403637210038319104
1403637210088318976
1403637210138319104
1403637210188318976
1403637210238319104
1403637210288318976
1403637210338319104
1403637210388318976
1403637210438319104
1403637210488318976
1403637210538319104
1403637210588318976
1403637210638319104
1403637210688318976
1403637210738319104
1403637210788318976
1403637210838319104
1403637210888318976
1403637210938319104
1403637210988318976
1403637211038319104
1403637211088318976
1403637211138319104
1403637211188318976
1403637211238319104
1403637211288318976
1403637211338319104
1403637211388318976
1403637211438319104
1403637211488318976
1403637211538319104
1403637211588318976
1403637211638319104
1403637211688318976
1403637211738319104
1403637211788318976
1403637211838319104
1403637211888318976
1403637211938319104
1403637211988318976
1403637212038319104
1403637212088318976
1403637212138319104
1403637212188318976
1403637212238319104
1403637212288318976
1403637212338319104
1403637212388318976
1403637212438319104
1403637212488318976
1403637212538319104
1403637212588318976
1403637212638319104
1403637212688318976
1403637212738319104
1403637212788318976
1403637212838319104
1403637212888318976
1403637212938319104
1403637212988318976
1403637213038319104
1403637213088318976
1403637213138319104
1403637213188318976
1403637213238319104
1403637213288318976
1403637213338319104
1403637213388318976
1403637213438319104
1403637213488318976
1403637213538319104
1403637213588318976
1403637213638319104
1403637213688318976
1403637213738319104
1403637213788318976
1403637213838319104
1403637213888318976
1403637213938319104
1403637213988318976
1403637214038319104
1403637214088318976
1403637214138319104
1403637214188318976
1403637214238319104
1403637214288318976
1403637214338319104
1403637214388318976
1403637214438319104
1403637214488318976
1403637214538319104
1403637214588318976
1403637214638319104
1403637214688318976
1403637214738319104
1403637214788318976
1403637214838319104
1403637214888318976
1403637214938319104
1403637214988318976
1403637215038319104
1403637215088318976
1403637215138319104
1403637215188318976
1403637215238319104
1403637215288318976
1403637215338319104
1403637215388318976
1403637215438319104
1403637215488318976
1403637215538319104
1403637215588318976
1403637215638319104
1403637215688318976
1403637215738319104
1403637215788318976
1403637215838319104
1403637215888318976
1403637215938319104
1403637215988318976
1403637216038319104
1403637216088318976
1403637216138319104
1403637216188318976
1403637216238319104
1403637216288318976
1403637216338319104
1403637216388318976
1403637216438319104
1403637216488318976
1403637216538319104
1403637216588318976
1403637216638319104
1403637216688318976
1403637216738319104
1403637216788318976
1403637216838319104
1403637216888318976
1403637216938319104
1403637216988318976
1403637217038319104
1403637217088318976
1403637217138319104
1403637217188318976
1403637217238319104
1403637217288318976
1403637217338319104
1403637217388318976
1403637217438319104
1403637217488318976
1403637217538319104
1403637217588318976
1403637217638319104
1403637217688318976
1403637217738319104
1403637217788318976
1403637217838319104
1403637217888318976
1403637217938319104
1403637217988318976
1403637218038319104
1403637218088318976
1403637218138319104
1403637218188318976
1403637218238319104
1403637218288318976
1403637218338319104
1403637218388318976
1403637218438319104
1403637218488318976
1403637218538319104
1403637218588318976
1403637218638319104
1403637218688318976
1403637218738319104
1403637218788318976
1403637218838319104
1403637218888318976
1403637218938319104
1403637218988318976
1403637219038319104
1403637219088318976
1403637219138319104
1403637219188318976
1403637219238319104
1403637219288318976
1403637219338319104
1403637219388318976
1403637219438319104
1403637219488318976
1403637219538319104
1403637219588318976
1403637219638319104
1403637219688318976
1403637219738319104
1403637219788318976
1403637219838319104
1403637219888318976
1403637219938319104
1403637219988318976
1403637220038319104
1403637220088318976
1403637220138319104
1403637220188318976
1403637220238319104
1403637220288318976
1403637220338319104
1403637220388318976
1403637220438319104
1403637220488318976
1403637220538319104
1403637220588318976
1403637220638319104
1403637220688318976
1403637220738319104
1403637220788318976
1403637220838319104
1403637220888318976
1403637220938319104
1403637220988318976
1403637221038319104
1403637221088318976
1403637221138319104
1403637221188318976
1403637221238319104
1403637221288318976
1403637221338319104
1403637221388318976
1403637221438319104
1403637221488318976
1403637221538319104
1403637221588318976
1403637221638319104
1403637221688318976
1403637221738319104
1403637221788318976
1403637221838319104
1403637221888318976
1403637221938319104
1403637221988318976
1403637222038319104
1403637222088318976
1403637222138319104
1403637222188318976
1403637222238319104
1403637222288318976
1403637222338319104
1403637222388318976
1403637222438319104
1403637222488318976
1403637222538319104
1403637222588318976
1403637222638319104
1403637222688318976
1403637222738319104
1403637222788318976
1403637222838319104
1403637222888318976
1403637222938319104
1403637222988318976
1403637223038319104
1403637223088318976
1403637223138319104
1403637223188318976
1403637223238319104
1403637223288318976
1403637223338319104
1403637223388318976
1403637223438319104
1403637223488318976
1403637223538319104
1403637223588318976
1403637223638319104
1403637223688318976
1403637223738319104
1403637223788318976
1403637223838319104
1403637223888318976
1403637223938319104
1403637223988318976
1403637224038319104
1403637224088318976
1403637224138319104
1403637224188318976
1403637224238319104
1403637224288318976
1403637224338319104
1403637224388318976
1403637224438319104
1403637224488318976
1403637224538319104
1403637224588318976
1403637224638319104
1403637224688318976
1403637224738319104
1403637224788318976
1403637224838319104
1403637224888318976
1403637224938319104
1403637224988318976
1403637225038319104
1403637225088318976
1403637225138319104
1403637225188318976
1403637225238319104
1403637225288318976
1403637225338319104
1403637225388318976
1403637225438319104
1403637225488318976
1403637225538319104
1403637225588318976
1403637225638319104
1403637225688318976
1403637225738319104
1403637225788318976
1403637225838319104
1403637225888318976
1403637225938319104
1403637225988318976
1403637226038319104
1403637226088318976
1403637226138319104
1403637226188318976
1403637226238319104
1403637226288318976
1403637226338319104
1403637226388318976
1403637226438319104
1403637226488318976
1403637226538319104
1403637226588318976
1403637226638319104
1403637226688318976
1403637226738319104
1403637226788318976
1403637226838319104
1403637226888318976
1403637226938319104
1403637226988318976
1403637227038319104
1403637227088318976
1403637227138319104
1403637227188318976
1403637227238319104
1403637227288318976
1403637227338319104
1403637227388318976
1403637227438319104
1403637227488318976
1403637227538319104
1403637227588318976
1403637227638319104
1403637227688318976
1403637227738319104
1403637227788318976
1403637227838319104
1403637227888318976
1403637227938319104
1403637227988318976
1403637228038319104
1403637228088318976
1403637228138319104
1403637228188318976
1403637228238319104
1403637228288318976
1403637228338319104
1403637228388318976
1403637228438319104
1403637228488318976
1403637228538319104
1403637228588318976
1403637228638319104
1403637228688318976
1403637228738319104
1403637228788318976
1403637228838319104
1403637228888318976
1403637228938319104
1403637228988318976
1403637229038319104
1403637229088318976
1403637229138319104
1403637229188318976
1403637229238319104
1403637229288318976
1403637229338319104
1403637229388318976
1403637229438319104
1403637229488318976
1403637229538319104
1403637229588318976
1403637229638319104
1403637229688318976
1403637229738319104
1403637229788318976
1403637229838319104
1403637229888318976
1403637229938319104
1403637229988318976
1403637230038319104
1403637230088318976
1403637230138319104
1403637230188318976
1403637230238319104
1403637230288318976
1403637230338319104
1403637230388318976
1403637230438319104
1403637230488318976
1403637230538319104
1403637230588318976
1403637230638319104
1403637230688318976
1403637230738319104
1403637230788318976
1403637230838319104
1403637230888318976
1403637230938319104
1403637230988318976
1403637231038319104
1403637231088318976
1403637231138319104
1403637231188318976
1403637231238319104
1403637231288318976
1403637231338319104
1403637231388318976
1403637231438319104
1403637231488318976
1403637231538319104
1403637231588318976
1403637231638319104
1403637231688318976
1403637231738319104
1403637231788318976
1403637231838319104
1403637231888318976
1403637231938319104
1403637231988318976
1403637232038319104
1403637232088318976
1403637232138319104
1403637232188318976
1403637232238319104
1403637232288318976
1403637232338319104
1403637232388318976
1403637232438319104
1403637232488318976
1403637232538319104
1403637232588318976
1403637232638319104
1403637232688318976
1403637232738319104
1403637232788318976
1403637232838319104
1403637232888318976
1403637232938319104
1403637232988318976
1403637233038319104
1403637233088318976
1403637233138319104
1403637233188318976
1403637233238319104
1403637233288318976
1403637233338319104
1403637233388318976
1403637233438319104
1403637233488318976
1403637233538319104
1403637233588318976
1403637233638319104
1403637233688318976
1403637233738319104
1403637233788318976
1403637233838319104
1403637233888318976
1403637233938319104
1403637233988318976
1403637234038319104
1403637234088318976
1403637234138319104
1403637234188318976
1403637234238319104
1403637234288318976
1403637234338319104
1403637234388318976
1403637234438319104
1403637234488318976
1403637234538319104
1403637234588318976
1403637234638319104
1403637234688318976
1403637234738319104
1403637234788318976
1403637234838319104
1403637234888318976
1403637234938319104
1403637234988318976
1403637235038319104
1403637235088318976
1403637235138319104
1403637235188318976
1403637235238319104
1403637235288318976
1403637235338319104
1403637235388318976
1403637235438319104
1403637235488318976
1403637235538319104
1403637235588318976
1403637235638319104
1403637235688318976
1403637235738319104
1403637235788318976
1403637235838319104
1403637235888318976
1403637235938319104
1403637235988318976
1403637236038319104
1403637236088318976
1403637236138319104
1403637236188318976
1403637236238319104
1403637236288318976
1403637236338319104
1403637236388318976
1403637236438319104
1403637236488318976
1403637236538319104
1403637236588318976
1403637236638319104
1403637236688318976
1403637236738319104
1403637236788318976
1403637236838319104
1403637236888318976
1403637236938319104
1403637236988318976
1403637237038319104
1403637237088318976
1403637237138319104
1403637237188318976
1403637237238319104
1403637237288318976
1403637237338319104
1403637237388318976
1403637237438319104
1403637237488318976
1403637237538319104
1403637237588318976
1403637237638319104
1403637237688318976
1403637237738319104
1403637237788318976
1403637237838319104
1403637237888318976
1403637237938319104
1403637237988318976
1403637238038319104
1403637238088318976
1403637238138319104
1403637238188318976
1403637238238319104
1403637238288318976
1403637238338319104
1403637238388318976
1403637238438319104
1403637238488318976
1403637238538319104
1403637238588318976
1403637238638319104
1403637238688318976
1403637238738319104
1403637238788318976
1403637238838319104
1403637238888318976
1403637238938319104
1403637238988318976
1403637239038319104
1403637239088318976
1403637239138319104
1403637239188318976
1403637239238319104
1403637239288318976
1403637239338319104
1403637239388318976
1403637239438319104
1403637239488318976
1403637239538319104
1403637239588318976
1403637239638319104
1403637239688318976
1403637239738319104
1403637239788318976
1403637239838319104
1403637239888318976
1403637239938319104
1403637239988318976
1403637240038319104
1403637240088318976
1403637240138319104
1403637240188318976
1403637240238319104
1403637240288318976
1403637240338319104
1403637240388318976
1403637240438319104
1403637240488318976
1403637240538319104
1403637240588318976
1403637240638319104
1403637240688318976
1403637240738319104
1403637240788318976
1403637240838319104
1403637240888318976
1403637240938319104
1403637240988318976
1403637241038319104
1403637241088318976
1403637241138319104
1403637241188318976
1403637241238319104
1403637241288318976
1403637241338319104
1403637241388318976
1403637241438319104
1403637241488318976
1403637241538319104
1403637241588318976
1403637241638319104
1403637241688318976
1403637241738319104
1403637241788318976
1403637241838319104
1403637241888318976
1403637241938319104
1403637241988318976
1403637242038319104
1403637242088318976
1403637242138319104
1403637242188318976
1403637242238319104
1403637242288318976
1403637242338319104
1403637242388318976
1403637242438319104
1403637242488318976
1403637242538319104
1403637242588318976
1403637242638319104
1403637242688318976
1403637242738319104
1403637242788318976
1403637242838319104
1403637242888318976
1403637242938319104
1403637242988318976
1403637243038319104
1403637243088318976
1403637243138319104
1403637243188318976
1403637243238319104
1403637243288318976
1403637243338319104
1403637243388318976
1403637243438319104
1403637243488318976
1403637243538319104
1403637243588318976
1403637243638319104
1403637243688318976
1403637243738319104
1403637243788318976
1403637243838319104
1403637243888318976
1403637243938319104
1403637243988318976
1403637244038319104
1403637244088318976
1403637244138319104
1403637244188318976
1403637244238319104
1403637244288318976
1403637244338319104
1403637244388318976
1403637244438319104
1403637244488318976
1403637244538319104
1403637244588318976
1403637244638319104
1403637244688318976
1403637244738319104
1403637244788318976
1403637244838319104
1403637244888318976
1403637244938319104
1403637244988318976
1403637245038319104
1403637245088318976
1403637245138319104
1403637245188318976
1403637245238319104
1403637245288318976
1403637245338319104
1403637245388318976
1403637245438319104
1403637245488318976
1403637245538319104
1403637245588318976
1403637245638319104
1403637245688318976
1403637245738319104
1403637245788318976
1403637245838319104
1403637245888318976
1403637245938319104
1403637245988318976
1403637246038319104
1403637246088318976
1403637246138319104
1403637246188318976
1403637246238319104
1403637246288318976
1403637246338319104
1403637246388318976
1403637246438319104
1403637246488318976
1403637246538319104
1403637246588318976
1403637246638319104
1403637246688318976
1403637246738319104
1403637246788318976
1403637246838319104
1403637246888318976
1403637246938319104
1403637246988318976
1403637247038319104
1403637247088318976
1403637247138319104
1403637247188318976
1403637247238319104
1403637247288318976
1403637247338319104
1403637247388318976
1403637247438319104
1403637247488318976
1403637247538319104
1403637247588318976
1403637247638319104
1403637247688318976
1403637247738319104
1403637247788318976
1403637247838319104
1403637247888318976
1403637247938319104
1403637247988318976
1403637248038319104
1403637248088318976
1403637248138319104
1403637248188318976
1403637248238319104
1403637248288318976
1403637248338319104
1403637248388318976
1403637248438319104
1403637248488318976
1403637248538319104
1403637248588318976
1403637248638319104
1403637248688318976
1403637248738319104
1403637248788318976
1403637248838319104
1403637248888318976
1403637248938319104
1403637248988318976
1403637249038319104
1403637249088318976
1403637249138319104
1403637249188318976
1403637249238319104
1403637249288318976
1403637249338319104
1403637249388318976
1403637249438319104
1403637249488318976
1403637249538319104
1403637249588318976
1403637249638319104
1403637249688318976
1403637249738319104
1403637249788318976
1403637249838319104
1403637249888318976
1403637249938319104
1403637249988318976
1403637250038319104
1403637250088318976
1403637250138319104
1403637250188318976
1403637250238319104
1403637250288318976
1403637250338319104
1403637250388318976
1403637250438319104
1403637250488318976
1403637250538319104
1403637250588318976
1403637250638319104
1403637250688318976
1403637250738319104
1403637250788318976
1403637250838319104
1403637250888318976
1403637250938319104
1403637250988318976
1403637251038319104
1403637251088318976
1403637251138319104
1403637251188318976
1403637251238319104
1403637251288318976
1403637251338319104
1403637251388318976
1403637251438319104
1403637251488318976
1403637251538319104
1403637251588318976
1403637251638319104
1403637251688318976
1403637251738319104
1403637251788318976
1403637251838319104
1403637251888318976
1403637251938319104
1403637251988318976
1403637252038319104
1403637252088318976
1403637252138319104
1403637252188318976
1403637252238319104
1403637252288318976
1403637252338319104
1403637252388318976
1403637252438319104
1403637252488318976
1403637252538319104
1403637252588318976
1403637252638319104
1403637252688318976
1403637252738319104
1403637252788318976
1403637252838319104
1403637252888318976
1403637252938319104
1403637252988318976
1403637253038319104
1403637253088318976
1403637253138319104
1403637253188318976
1403637253238319104
1403637253288318976
1403637253338319104
1403637253388318976
1403637253438319104
1403637253488318976
1403637253538319104
1403637253588318976
1403637253638319104
1403637253688318976
1403637253738319104
1403637253788318976
1403637253838319104
1403637253888318976
1403637253938319104
1403637253988318976
1403637254038319104
1403637254088318976
1403637254138319104
1403637254188318976
1403637254238319104
1403637254288318976
1403637254338319104
1403637254388318976
1403637254438319104
1403637254488318976
1403637254538319104
1403637254588318976
1403637254638319104
1403637254688318976
1403637254738319104
1403637254788318976
1403637254838319104
1403637254888318976
1403637254938319104
1403637254988318976
1403637255038319104
1403637255088318976
1403637255138319104
1403637255188318976
1403637255238319104
1403637255288318976
1403637255338319104
1403637255388318976
1403637255438319104
1403637255488318976
1403637255538319104
1403637255588318976
1403637255638319104
1403637255688318976
1403637255738319104
1403637255788318976
1403637255838319104
1403637255888318976
1403637255938319104
1403637255988318976
1403637256038319104
1403637256088318976
1403637256138319104
1403637256188318976
1403637256238319104
1403637256288318976
1403637256338319104
1403637256388318976
1403637256438319104
1403637256488318976
1403637256538319104
1403637256588318976
1403637256638319104
1403637256688318976
1403637256738319104
1403637256788318976
1403637256838319104
1403637256888318976
1403637256938319104
1403637256988318976
1403637257038319104
1403637257088318976
1403637257138319104
1403637257188318976
1403637257238319104
1403637257288318976
1403637257338319104
1403637257388318976
1403637257438319104
1403637257488318976
1403637257538319104
1403637257588318976
1403637257638319104
1403637257688318976
1403637257738319104
1403637257788318976
1403637257838319104
1403637257888318976
1403637257938319104
1403637257988318976
1403637258038319104
1403637258088318976
1403637258138319104
1403637258188318976
1403637258238319104
1403637258288318976
1403637258338319104
1403637258388318976
1403637258438319104
1403637258488318976
1403637258538319104
1403637258588318976
1403637258638319104
1403637258688318976
1403637258738319104
1403637258788318976
1403637258838319104
1403637258888318976
1403637258938319104
1403637258988318976
1403637259038319104
1403637259088318976
1403637259138319104
1403637259188318976
1403637259238319104
1403637259288318976
1403637259338319104
1403637259388318976
1403637259438319104
1403637259488318976
1403637259538319104
1403637259588318976
1403637259638319104
1403637259688318976
1403637259738319104
1403637259788318976
1403637259838319104
1403637259888318976
1403637259938319104
1403637259988318976
1403637260038319104
1403637260088318976
1403637260138319104
1403637260188318976
1403637260238319104
1403637260288318976
1403637260338319104
1403637260388318976
1403637260438319104
1403637260488318976
1403637260538319104
1403637260588318976
1403637260638319104
1403637260688318976
1403637260738319104
1403637260788318976
1403637260838319104
1403637260888318976
1403637260938319104
1403637260988318976
1403637261038319104
1403637261088318976
1403637261138319104
1403637261188318976
1403637261238319104
1403637261288318976
1403637261338319104
1403637261388318976
1403637261438319104
1403637261488318976
1403637261538319104
1403637261588318976
1403637261638319104
1403637261688318976
1403637261738319104
1403637261788318976
1403637261838319104
1403637261888318976
1403637261938319104
1403637261988318976
1403637262038319104
1403637262088318976
1403637262138319104
1403637262188318976
1403637262238319104
1403637262288318976
1403637262338319104
1403637262388318976
1403637262438319104
1403637262488318976
1403637262538319104
1403637262588318976
1403637262638319104
1403637262688318976
1403637262738319104
1403637262788318976
1403637262838319104
1403637262888318976
1403637262938319104
1403637262988318976
1403637263038319104
1403637263088318976
1403637263138319104
1403637263188318976
1403637263238319104
1403637263288318976
1403637263338319104
1403637263388318976
1403637263438319104
1403637263488318976
1403637263538319104
1403637263588318976
1403637263638319104
1403637263688318976
1403637263738319104
1403637263788318976
1403637263838319104
1403637263888318976
1403637263938319104
1403637263988318976
1403637264038319104
1403637264088318976
1403637264138319104
1403637264188318976
1403637264238319104
1403637264288318976
1403637264338319104
1403637264388318976
1403637264438319104
1403637264488318976
1403637264538319104
1403637264588318976
1403637264638319104
1403637264688318976
1403637264738319104
1403637264788318976
1403637264838319104
1403637264888318976
1403637264938319104
1403637264988318976
1403637265038319104
1403637265088318976
1403637265138319104
1403637265188318976
1403637265238319104
1403637265288318976
1403637265338319104
1403637265388318976
1403637265438319104
1403637265488318976
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/MH04.txt
================================================
1403638127245096960
1403638127295097088
1403638127345096960
1403638127395097088
1403638127445096960
1403638127495097088
1403638127545096960
1403638127595097088
1403638127645096960
1403638127695097088
1403638127745096960
1403638127795097088
1403638127845096960
1403638127895097088
1403638127945096960
1403638127995097088
1403638128045096960
1403638128095097088
1403638128145096960
1403638128195097088
1403638128245096960
1403638128295097088
1403638128345096960
1403638128395097088
1403638128445096960
1403638128495097088
1403638128545096960
1403638128595097088
1403638128645096960
1403638128695097088
1403638128745096960
1403638128795097088
1403638128845096960
1403638128895097088
1403638128945096960
1403638128995097088
1403638129045096960
1403638129095097088
1403638129145096960
1403638129195097088
1403638129245096960
1403638129295097088
1403638129345096960
1403638129395097088
1403638129445096960
1403638129495097088
1403638129545096960
1403638129595097088
1403638129645096960
1403638129695097088
1403638129745096960
1403638129795097088
1403638129845096960
1403638129895097088
1403638129945096960
1403638129995097088
1403638130045096960
1403638130095097088
1403638130145096960
1403638130195097088
1403638130245096960
1403638130295097088
1403638130345096960
1403638130395097088
1403638130445096960
1403638130495097088
1403638130545096960
1403638130595097088
1403638130645096960
1403638130695097088
1403638130745096960
1403638130795097088
1403638130845096960
1403638130895097088
1403638130945096960
1403638130995097088
1403638131045096960
1403638131095097088
1403638131145096960
1403638131195097088
1403638131245096960
1403638131295097088
1403638131345096960
1403638131395097088
1403638131445096960
1403638131495097088
1403638131545096960
1403638131595097088
1403638131645096960
1403638131695097088
1403638131745096960
1403638131795097088
1403638131845096960
1403638131895097088
1403638131945096960
1403638131995097088
1403638132045096960
1403638132095097088
1403638132145096960
1403638132195097088
1403638132245096960
1403638132295097088
1403638132345096960
1403638132395097088
1403638132445096960
1403638132495097088
1403638132545096960
1403638132595097088
1403638132645096960
1403638132695097088
1403638132745096960
1403638132795097088
1403638132845096960
1403638132895097088
1403638132945096960
1403638132995097088
1403638133045096960
1403638133095097088
1403638133145096960
1403638133195097088
1403638133245096960
1403638133295097088
1403638133345096960
1403638133395097088
1403638133445096960
1403638133495097088
1403638133545096960
1403638133595097088
1403638133645096960
1403638133695097088
1403638133745096960
1403638133795097088
1403638133845096960
1403638133895097088
1403638133945096960
1403638133995097088
1403638134045096960
1403638134095097088
1403638134145096960
1403638134195097088
1403638134245096960
1403638134295097088
1403638134345096960
1403638134395097088
1403638134445096960
1403638134495097088
1403638134545096960
1403638134595097088
1403638134645096960
1403638134695097088
1403638134745096960
1403638134795097088
1403638134845096960
1403638134895097088
1403638134945096960
1403638134995097088
1403638135045096960
1403638135095097088
1403638135145096960
1403638135195097088
1403638135245096960
1403638135295097088
1403638135345096960
1403638135395097088
1403638135445096960
1403638135495097088
1403638135545096960
1403638135595097088
1403638135645096960
1403638135695097088
1403638135745096960
1403638135795097088
1403638135845096960
1403638135895097088
1403638135945096960
1403638135995097088
1403638136045096960
1403638136095097088
1403638136145096960
1403638136195097088
1403638136245096960
1403638136295097088
1403638136345096960
1403638136395097088
1403638136445096960
1403638136495097088
1403638136545096960
1403638136595097088
1403638136645096960
1403638136695097088
1403638136745096960
1403638136795097088
1403638136845096960
1403638136895097088
1403638136945096960
1403638136995097088
1403638137045096960
1403638137095097088
1403638137145096960
1403638137195097088
1403638137245096960
1403638137295097088
1403638137345096960
1403638137395097088
1403638137445096960
1403638137495097088
1403638137545096960
1403638137595097088
1403638137645096960
1403638137695097088
1403638137745096960
1403638137795097088
1403638137845096960
1403638137895097088
1403638137945096960
1403638137995097088
1403638138045096960
1403638138095097088
1403638138145096960
1403638138195097088
1403638138245096960
1403638138295097088
1403638138345096960
1403638138395097088
1403638138445096960
1403638138495097088
1403638138545096960
1403638138595097088
1403638138645096960
1403638138695097088
1403638138745096960
1403638138795097088
1403638138845096960
1403638138895097088
1403638138945096960
1403638138995097088
1403638139045096960
1403638139095097088
1403638139145096960
1403638139195097088
1403638139245096960
1403638139295097088
1403638139345096960
1403638139395097088
1403638139445096960
1403638139495097088
1403638139545096960
1403638139595097088
1403638139645096960
1403638139695097088
1403638139745096960
1403638139795097088
1403638139845096960
1403638139895097088
1403638139945096960
1403638139995097088
1403638140045096960
1403638140095097088
1403638140145096960
1403638140195097088
1403638140245096960
1403638140295097088
1403638140345096960
1403638140395097088
1403638140445096960
1403638140495097088
1403638140545096960
1403638140595097088
1403638140645096960
1403638140695097088
1403638140745096960
1403638140795097088
1403638140845096960
1403638140895097088
1403638140945096960
1403638140995097088
1403638141045096960
1403638141095097088
1403638141145096960
1403638141195097088
1403638141245096960
1403638141295097088
1403638141345096960
1403638141395097088
1403638141445096960
1403638141495097088
1403638141545096960
1403638141595097088
1403638141645096960
1403638141695097088
1403638141745096960
1403638141795097088
1403638141845096960
1403638141895097088
1403638141945096960
1403638141995097088
1403638142045096960
1403638142095097088
1403638142145096960
1403638142195097088
1403638142245096960
1403638142295097088
1403638142345096960
1403638142395097088
1403638142445096960
1403638142495097088
1403638142545096960
1403638142595097088
1403638142645096960
1403638142695097088
1403638142745096960
1403638142795097088
1403638142845096960
1403638142895097088
1403638142945096960
1403638142995097088
1403638143045096960
1403638143095097088
1403638143145096960
1403638143195097088
1403638143245096960
1403638143295097088
1403638143345096960
1403638143395097088
1403638143445096960
1403638143495097088
1403638143545096960
1403638143595097088
1403638143645096960
1403638143695097088
1403638143745096960
1403638143795097088
1403638143845096960
1403638143895097088
1403638143945096960
1403638143995097088
1403638144045096960
1403638144095097088
1403638144145096960
1403638144195097088
1403638144245096960
1403638144295097088
1403638144345096960
1403638144395097088
1403638144445096960
1403638144495097088
1403638144545096960
1403638144595097088
1403638144645096960
1403638144695097088
1403638144745096960
1403638144795097088
1403638144845096960
1403638144895097088
1403638144945096960
1403638144995097088
1403638145045096960
1403638145095097088
1403638145145096960
1403638145195097088
1403638145245096960
1403638145295097088
1403638145345096960
1403638145395097088
1403638145445096960
1403638145495097088
1403638145545096960
1403638145595097088
1403638145645096960
1403638145695097088
1403638145745096960
1403638145795097088
1403638145845096960
1403638145895097088
1403638145945096960
1403638145995097088
1403638146045096960
1403638146095097088
1403638146145096960
1403638146195097088
1403638146245096960
1403638146295097088
1403638146345096960
1403638146395097088
1403638146445096960
1403638146495097088
1403638146545096960
1403638146595097088
1403638146645096960
1403638146695097088
1403638146745096960
1403638146795097088
1403638146845096960
1403638146895097088
1403638146945096960
1403638146995097088
1403638147045096960
1403638147095097088
1403638147145096960
1403638147195097088
1403638147245096960
1403638147295097088
1403638147345096960
1403638147395097088
1403638147445096960
1403638147495097088
1403638147545096960
1403638147595097088
1403638147645096960
1403638147695097088
1403638147745096960
1403638147795097088
1403638147845096960
1403638147895097088
1403638147945096960
1403638147995097088
1403638148045096960
1403638148095097088
1403638148145096960
1403638148195097088
1403638148245096960
1403638148295097088
1403638148345096960
1403638148395097088
1403638148445096960
1403638148495097088
1403638148545096960
1403638148595097088
1403638148645096960
1403638148695097088
1403638148745096960
1403638148795097088
1403638148845096960
1403638148895097088
1403638148945096960
1403638148995097088
1403638149045096960
1403638149095097088
1403638149145096960
1403638149195097088
1403638149245096960
1403638149295097088
1403638149345096960
1403638149395097088
1403638149445096960
1403638149495097088
1403638149545096960
1403638149595097088
1403638149645096960
1403638149695097088
1403638149745096960
1403638149795097088
1403638149845096960
1403638149895097088
1403638149945096960
1403638149995097088
1403638150045096960
1403638150095097088
1403638150145096960
1403638150195097088
1403638150245096960
1403638150295097088
1403638150345096960
1403638150395097088
1403638150445096960
1403638150495097088
1403638150545096960
1403638150595097088
1403638150645096960
1403638150695097088
1403638150745096960
1403638150795097088
1403638150845096960
1403638150895097088
1403638150945096960
1403638150995097088
1403638151045096960
1403638151095097088
1403638151145096960
1403638151195097088
1403638151245096960
1403638151295097088
1403638151345096960
1403638151395097088
1403638151445096960
1403638151495097088
1403638151545096960
1403638151595097088
1403638151645096960
1403638151695097088
1403638151745096960
1403638151795097088
1403638151845096960
1403638151895097088
1403638151945096960
1403638151995097088
1403638152045096960
1403638152095097088
1403638152145096960
1403638152195097088
1403638152245096960
1403638152295097088
1403638152345096960
1403638152395097088
1403638152445096960
1403638152495097088
1403638152545096960
1403638152595097088
1403638152645096960
1403638152695097088
1403638152745096960
1403638152795097088
1403638152845096960
1403638152895097088
1403638152945096960
1403638152995097088
1403638153045096960
1403638153095097088
1403638153145096960
1403638153195097088
1403638153245096960
1403638153295097088
1403638153345096960
1403638153395097088
1403638153445096960
1403638153495097088
1403638153545096960
1403638153595097088
1403638153645096960
1403638153695097088
1403638153745096960
1403638153795097088
1403638153845096960
1403638153895097088
1403638153945096960
1403638153995097088
1403638154045096960
1403638154095097088
1403638154145096960
1403638154195097088
1403638154245096960
1403638154295097088
1403638154345096960
1403638154395097088
1403638154445096960
1403638154495097088
1403638154545096960
1403638154595097088
1403638154645096960
1403638154695097088
1403638154745096960
1403638154795097088
1403638154845096960
1403638154895097088
1403638154945096960
1403638154995097088
1403638155045096960
1403638155095097088
1403638155145096960
1403638155195097088
1403638155245096960
1403638155295097088
1403638155345096960
1403638155395097088
1403638155445096960
1403638155495097088
1403638155545096960
1403638155595097088
1403638155645096960
1403638155695097088
1403638155745096960
1403638155795097088
1403638155845096960
1403638155895097088
1403638155945096960
1403638155995097088
1403638156045096960
1403638156095097088
1403638156145096960
1403638156195097088
1403638156245096960
1403638156295097088
1403638156345096960
1403638156395097088
1403638156445096960
1403638156495097088
1403638156545096960
1403638156595097088
1403638156645096960
1403638156695097088
1403638156745096960
1403638156795097088
1403638156845096960
1403638156895097088
1403638156945096960
1403638156995097088
1403638157045096960
1403638157095097088
1403638157145096960
1403638157195097088
1403638157245096960
1403638157295097088
1403638157345096960
1403638157395097088
1403638157445096960
1403638157495097088
1403638157545096960
1403638157595097088
1403638157645096960
1403638157695097088
1403638157745096960
1403638157795097088
1403638157845096960
1403638157895097088
1403638157945096960
1403638157995097088
1403638158045096960
1403638158095097088
1403638158145096960
1403638158195097088
1403638158245096960
1403638158295097088
1403638158345096960
1403638158395097088
1403638158445096960
1403638158495097088
1403638158545096960
1403638158595097088
1403638158645096960
1403638158695097088
1403638158745096960
1403638158795097088
1403638158845096960
1403638158895097088
1403638158945096960
1403638158995097088
1403638159045096960
1403638159095097088
1403638159145096960
1403638159195097088
1403638159245096960
1403638159295097088
1403638159345096960
1403638159395097088
1403638159445096960
1403638159495097088
1403638159545096960
1403638159595097088
1403638159645096960
1403638159695097088
1403638159745096960
1403638159795097088
1403638159845096960
1403638159895097088
1403638159945096960
1403638159995097088
1403638160045096960
1403638160095097088
1403638160145096960
1403638160195097088
1403638160245096960
1403638160295097088
1403638160345096960
1403638160395097088
1403638160445096960
1403638160495097088
1403638160545096960
1403638160595097088
1403638160645096960
1403638160695097088
1403638160745096960
1403638160795097088
1403638160845096960
1403638160895097088
1403638160945096960
1403638160995097088
1403638161045096960
1403638161095097088
1403638161145096960
1403638161195097088
1403638161245096960
1403638161295097088
1403638161345096960
1403638161395097088
1403638161445096960
1403638161495097088
1403638161545096960
1403638161595097088
1403638161645096960
1403638161695097088
1403638161745096960
1403638161795097088
1403638161845096960
1403638161895097088
1403638161945096960
1403638161995097088
1403638162045096960
1403638162095097088
1403638162145096960
1403638162195097088
1403638162245096960
1403638162295097088
1403638162345096960
1403638162395097088
1403638162445096960
1403638162495097088
1403638162545096960
1403638162595097088
1403638162645096960
1403638162695097088
1403638162745096960
1403638162795097088
1403638162845096960
1403638162895097088
1403638162945096960
1403638162995097088
1403638163045096960
1403638163095097088
1403638163145096960
1403638163195097088
1403638163245096960
1403638163295097088
1403638163345096960
1403638163395097088
1403638163445096960
1403638163495097088
1403638163545096960
1403638163595097088
1403638163645096960
1403638163695097088
1403638163745096960
1403638163795097088
1403638163845096960
1403638163895097088
1403638163945096960
1403638163995097088
1403638164045096960
1403638164095097088
1403638164145096960
1403638164195097088
1403638164245096960
1403638164295097088
1403638164345096960
1403638164395097088
1403638164445096960
1403638164495097088
1403638164545096960
1403638164595097088
1403638164645096960
1403638164695097088
1403638164745096960
1403638164795097088
1403638164845096960
1403638164895097088
1403638164945096960
1403638164995097088
1403638165045096960
1403638165095097088
1403638165145096960
1403638165195097088
1403638165245096960
1403638165295097088
1403638165345096960
1403638165395097088
1403638165445096960
1403638165495097088
1403638165545096960
1403638165595097088
1403638165645096960
1403638165695097088
1403638165745096960
1403638165795097088
1403638165845096960
1403638165895097088
1403638165945096960
1403638165995097088
1403638166045096960
1403638166095097088
1403638166145096960
1403638166195097088
1403638166245096960
1403638166295097088
1403638166345096960
1403638166395097088
1403638166445096960
1403638166495097088
1403638166545096960
1403638166595097088
1403638166645096960
1403638166695097088
1403638166745096960
1403638166795097088
1403638166845096960
1403638166895097088
1403638166945096960
1403638166995097088
1403638167045096960
1403638167095097088
1403638167145096960
1403638167195097088
1403638167245096960
1403638167295097088
1403638167345096960
1403638167395097088
1403638167445096960
1403638167495097088
1403638167545096960
1403638167595097088
1403638167645096960
1403638167695097088
1403638167745096960
1403638167795097088
1403638167845096960
1403638167895097088
1403638167945096960
1403638167995097088
1403638168045096960
1403638168095097088
1403638168145096960
1403638168195097088
1403638168245096960
1403638168295097088
1403638168345096960
1403638168395097088
1403638168445096960
1403638168495097088
1403638168545096960
1403638168595097088
1403638168645096960
1403638168695097088
1403638168745096960
1403638168795097088
1403638168845096960
1403638168895097088
1403638168945096960
1403638168995097088
1403638169045096960
1403638169095097088
1403638169145096960
1403638169195097088
1403638169245096960
1403638169295097088
1403638169345096960
1403638169395097088
1403638169445096960
1403638169495097088
1403638169545096960
1403638169595097088
1403638169645096960
1403638169695097088
1403638169745096960
1403638169795097088
1403638169845096960
1403638169895097088
1403638169945096960
1403638169995097088
1403638170045096960
1403638170095097088
1403638170145096960
1403638170195097088
1403638170245096960
1403638170295097088
1403638170345096960
1403638170395097088
1403638170445096960
1403638170495097088
1403638170545096960
1403638170595097088
1403638170645096960
1403638170695097088
1403638170745096960
1403638170795097088
1403638170845096960
1403638170895097088
1403638170945096960
1403638170995097088
1403638171045096960
1403638171095097088
1403638171145096960
1403638171195097088
1403638171245096960
1403638171295097088
1403638171345096960
1403638171395097088
1403638171445096960
1403638171495097088
1403638171545096960
1403638171595097088
1403638171645096960
1403638171695097088
1403638171745096960
1403638171795097088
1403638171845096960
1403638171895097088
1403638171945096960
1403638171995097088
1403638172045096960
1403638172095097088
1403638172145096960
1403638172195097088
1403638172245096960
1403638172295097088
1403638172345096960
1403638172395097088
1403638172445096960
1403638172495097088
1403638172545096960
1403638172595097088
1403638172645096960
1403638172695097088
1403638172745096960
1403638172795097088
1403638172845096960
1403638172895097088
1403638172945096960
1403638172995097088
1403638173045096960
1403638173095097088
1403638173145096960
1403638173195097088
1403638173245096960
1403638173295097088
1403638173345096960
1403638173395097088
1403638173445096960
1403638173495097088
1403638173545096960
1403638173595097088
1403638173645096960
1403638173695097088
1403638173745096960
1403638173795097088
1403638173845096960
1403638173895097088
1403638173945096960
1403638173995097088
1403638174045096960
1403638174095097088
1403638174145096960
1403638174195097088
1403638174245096960
1403638174295097088
1403638174345096960
1403638174395097088
1403638174445096960
1403638174495097088
1403638174545096960
1403638174595097088
1403638174645096960
1403638174695097088
1403638174745096960
1403638174795097088
1403638174845096960
1403638174895097088
1403638174945096960
1403638174995097088
1403638175045096960
1403638175095097088
1403638175145096960
1403638175195097088
1403638175245096960
1403638175295097088
1403638175345096960
1403638175395097088
1403638175445096960
1403638175495097088
1403638175545096960
1403638175595097088
1403638175645096960
1403638175695097088
1403638175745096960
1403638175795097088
1403638175845096960
1403638175895097088
1403638175945096960
1403638175995097088
1403638176045096960
1403638176095097088
1403638176145096960
1403638176195097088
1403638176245096960
1403638176295097088
1403638176345096960
1403638176395097088
1403638176445096960
1403638176495097088
1403638176545096960
1403638176595097088
1403638176645096960
1403638176695097088
1403638176745096960
1403638176795097088
1403638176845096960
1403638176895097088
1403638176945096960
1403638176995097088
1403638177045096960
1403638177095097088
1403638177145096960
1403638177195097088
1403638177245096960
1403638177295097088
1403638177345096960
1403638177395097088
1403638177445096960
1403638177495097088
1403638177545096960
1403638177595097088
1403638177645096960
1403638177695097088
1403638177745096960
1403638177795097088
1403638177845096960
1403638177895097088
1403638177945096960
1403638177995097088
1403638178045096960
1403638178095097088
1403638178145096960
1403638178195097088
1403638178245096960
1403638178295097088
1403638178345096960
1403638178395097088
1403638178445096960
1403638178495097088
1403638178545096960
1403638178595097088
1403638178645096960
1403638178695097088
1403638178745096960
1403638178795097088
1403638178845096960
1403638178895097088
1403638178945096960
1403638178995097088
1403638179045096960
1403638179095097088
1403638179145096960
1403638179195097088
1403638179245096960
1403638179295097088
1403638179345096960
1403638179395097088
1403638179445096960
1403638179495097088
1403638179545096960
1403638179595097088
1403638179645096960
1403638179695097088
1403638179745096960
1403638179795097088
1403638179845096960
1403638179895097088
1403638179945096960
1403638179995097088
1403638180045096960
1403638180095097088
1403638180145096960
1403638180195097088
1403638180245096960
1403638180295097088
1403638180345096960
1403638180395097088
1403638180445096960
1403638180495097088
1403638180545096960
1403638180595097088
1403638180645096960
1403638180695097088
1403638180745096960
1403638180795097088
1403638180845096960
1403638180895097088
1403638180945096960
1403638180995097088
1403638181045096960
1403638181095097088
1403638181145096960
1403638181195097088
1403638181245096960
1403638181295097088
1403638181345096960
1403638181395097088
1403638181445096960
1403638181495097088
1403638181545096960
1403638181595097088
1403638181645096960
1403638181695097088
1403638181745096960
1403638181795097088
1403638181845096960
1403638181895097088
1403638181945096960
1403638181995097088
1403638182045096960
1403638182095097088
1403638182145096960
1403638182195097088
1403638182245096960
1403638182295097088
1403638182345096960
1403638182395097088
1403638182445096960
1403638182495097088
1403638182545096960
1403638182595097088
1403638182645096960
1403638182695097088
1403638182745096960
1403638182795097088
1403638182845096960
1403638182895097088
1403638182945096960
1403638182995097088
1403638183045096960
1403638183095097088
1403638183145096960
1403638183195097088
1403638183245096960
1403638183295097088
1403638183345096960
1403638183395097088
1403638183445096960
1403638183495097088
1403638183545096960
1403638183595097088
1403638183645096960
1403638183695097088
1403638183745096960
1403638183795097088
1403638183845096960
1403638183895097088
1403638183945096960
1403638183995097088
1403638184045096960
1403638184095097088
1403638184145096960
1403638184195097088
1403638184245096960
1403638184295097088
1403638184345096960
1403638184395097088
1403638184445096960
1403638184495097088
1403638184545096960
1403638184595097088
1403638184645096960
1403638184695097088
1403638184745096960
1403638184795097088
1403638184845096960
1403638184895097088
1403638184945096960
1403638184995097088
1403638185045096960
1403638185095097088
1403638185145096960
1403638185195097088
1403638185245096960
1403638185295097088
1403638185345096960
1403638185395097088
1403638185445096960
1403638185495097088
1403638185545096960
1403638185595097088
1403638185645096960
1403638185695097088
1403638185745096960
1403638185795097088
1403638185845096960
1403638185895097088
1403638185945096960
1403638185995097088
1403638186045096960
1403638186095097088
1403638186145096960
1403638186195097088
1403638186245096960
1403638186295097088
1403638186345096960
1403638186395097088
1403638186445096960
1403638186495097088
1403638186545096960
1403638186595097088
1403638186645096960
1403638186695097088
1403638186745096960
1403638186795097088
1403638186845096960
1403638186895097088
1403638186945096960
1403638186995097088
1403638187045096960
1403638187095097088
1403638187145096960
1403638187195097088
1403638187245096960
1403638187295097088
1403638187345096960
1403638187395097088
1403638187445096960
1403638187495097088
1403638187545096960
1403638187595097088
1403638187645096960
1403638187695097088
1403638187745096960
1403638187795097088
1403638187845096960
1403638187895097088
1403638187945096960
1403638187995097088
1403638188045096960
1403638188095097088
1403638188145096960
1403638188195097088
1403638188245096960
1403638188295097088
1403638188345096960
1403638188395097088
1403638188445096960
1403638188495097088
1403638188545096960
1403638188595097088
1403638188645096960
1403638188695097088
1403638188745096960
1403638188795097088
1403638188845096960
1403638188895097088
1403638188945096960
1403638188995097088
1403638189045096960
1403638189095097088
1403638189145096960
1403638189195097088
1403638189245096960
1403638189295097088
1403638189345096960
1403638189395097088
1403638189445096960
1403638189495097088
1403638189545096960
1403638189595097088
1403638189645096960
1403638189695097088
1403638189745096960
1403638189795097088
1403638189845096960
1403638189895097088
1403638189945096960
1403638189995097088
1403638190045096960
1403638190095097088
1403638190145096960
1403638190195097088
1403638190245096960
1403638190295097088
1403638190345096960
1403638190395097088
1403638190445096960
1403638190495097088
1403638190545096960
1403638190595097088
1403638190645096960
1403638190695097088
1403638190745096960
1403638190795097088
1403638190845096960
1403638190895097088
1403638190945096960
1403638190995097088
1403638191045096960
1403638191095097088
1403638191145096960
1403638191195097088
1403638191245096960
1403638191295097088
1403638191345096960
1403638191395097088
1403638191445096960
1403638191495097088
1403638191545096960
1403638191595097088
1403638191645096960
1403638191695097088
1403638191745096960
1403638191795097088
1403638191845096960
1403638191895097088
1403638191945096960
1403638191995097088
1403638192045096960
1403638192095097088
1403638192145096960
1403638192195097088
1403638192245096960
1403638192295097088
1403638192345096960
1403638192395097088
1403638192445096960
1403638192495097088
1403638192545096960
1403638192595097088
1403638192645096960
1403638192695097088
1403638192745096960
1403638192795097088
1403638192845096960
1403638192895097088
1403638192945096960
1403638192995097088
1403638193045096960
1403638193095097088
1403638193145096960
1403638193195097088
1403638193245096960
1403638193295097088
1403638193345096960
1403638193395097088
1403638193445096960
1403638193495097088
1403638193545096960
1403638193595097088
1403638193645096960
1403638193695097088
1403638193745096960
1403638193795097088
1403638193845096960
1403638193895097088
1403638193945096960
1403638193995097088
1403638194045096960
1403638194095097088
1403638194145096960
1403638194195097088
1403638194245096960
1403638194295097088
1403638194345096960
1403638194395097088
1403638194445096960
1403638194495097088
1403638194545096960
1403638194595097088
1403638194645096960
1403638194695097088
1403638194745096960
1403638194795097088
1403638194845096960
1403638194895097088
1403638194945096960
1403638194995097088
1403638195045096960
1403638195095097088
1403638195145096960
1403638195195097088
1403638195245096960
1403638195295097088
1403638195345096960
1403638195395097088
1403638195445096960
1403638195495097088
1403638195545096960
1403638195595097088
1403638195645096960
1403638195695097088
1403638195745096960
1403638195795097088
1403638195845096960
1403638195895097088
1403638195945096960
1403638195995097088
1403638196045096960
1403638196095097088
1403638196145096960
1403638196195097088
1403638196245096960
1403638196295097088
1403638196345096960
1403638196395097088
1403638196445096960
1403638196495097088
1403638196545096960
1403638196595097088
1403638196645096960
1403638196695097088
1403638196745096960
1403638196795097088
1403638196845096960
1403638196895097088
1403638196945096960
1403638196995097088
1403638197045096960
1403638197095097088
1403638197145096960
1403638197195097088
1403638197245096960
1403638197295097088
1403638197345096960
1403638197395097088
1403638197445096960
1403638197495097088
1403638197545096960
1403638197595097088
1403638197645096960
1403638197695097088
1403638197745096960
1403638197795097088
1403638197845096960
1403638197895097088
1403638197945096960
1403638197995097088
1403638198045096960
1403638198095097088
1403638198145096960
1403638198195097088
1403638198245096960
1403638198295097088
1403638198345096960
1403638198395097088
1403638198445096960
1403638198495097088
1403638198545096960
1403638198595097088
1403638198645096960
1403638198695097088
1403638198745096960
1403638198795097088
1403638198845096960
1403638198895097088
1403638198945096960
1403638198995097088
1403638199045096960
1403638199095097088
1403638199145096960
1403638199195097088
1403638199245096960
1403638199295097088
1403638199345096960
1403638199395097088
1403638199445096960
1403638199495097088
1403638199545096960
1403638199595097088
1403638199645096960
1403638199695097088
1403638199745096960
1403638199795097088
1403638199845096960
1403638199895097088
1403638199945096960
1403638199995097088
1403638200045096960
1403638200095097088
1403638200145096960
1403638200195097088
1403638200245096960
1403638200295097088
1403638200345096960
1403638200395097088
1403638200445096960
1403638200495097088
1403638200545096960
1403638200595097088
1403638200645096960
1403638200695097088
1403638200745096960
1403638200795097088
1403638200845096960
1403638200895097088
1403638200945096960
1403638200995097088
1403638201045096960
1403638201095097088
1403638201145096960
1403638201195097088
1403638201245096960
1403638201295097088
1403638201345096960
1403638201395097088
1403638201445096960
1403638201495097088
1403638201545096960
1403638201595097088
1403638201645096960
1403638201695097088
1403638201745096960
1403638201795097088
1403638201845096960
1403638201895097088
1403638201945096960
1403638201995097088
1403638202045096960
1403638202095097088
1403638202145096960
1403638202195097088
1403638202245096960
1403638202295097088
1403638202345096960
1403638202395097088
1403638202445096960
1403638202495097088
1403638202545096960
1403638202595097088
1403638202645096960
1403638202695097088
1403638202745096960
1403638202795097088
1403638202845096960
1403638202895097088
1403638202945096960
1403638202995097088
1403638203045096960
1403638203095097088
1403638203145096960
1403638203195097088
1403638203245096960
1403638203295097088
1403638203345096960
1403638203395097088
1403638203445096960
1403638203495097088
1403638203545096960
1403638203595097088
1403638203645096960
1403638203695097088
1403638203745096960
1403638203795097088
1403638203845096960
1403638203895097088
1403638203945096960
1403638203995097088
1403638204045096960
1403638204095097088
1403638204145096960
1403638204195097088
1403638204245096960
1403638204295097088
1403638204345096960
1403638204395097088
1403638204445096960
1403638204495097088
1403638204545096960
1403638204595097088
1403638204645096960
1403638204695097088
1403638204745096960
1403638204795097088
1403638204845096960
1403638204895097088
1403638204945096960
1403638204995097088
1403638205045096960
1403638205095097088
1403638205145096960
1403638205195097088
1403638205245096960
1403638205295097088
1403638205345096960
1403638205395097088
1403638205445096960
1403638205495097088
1403638205545096960
1403638205595097088
1403638205645096960
1403638205695097088
1403638205745096960
1403638205795097088
1403638205845096960
1403638205895097088
1403638205945096960
1403638205995097088
1403638206045096960
1403638206095097088
1403638206145096960
1403638206195097088
1403638206245096960
1403638206295097088
1403638206345096960
1403638206395097088
1403638206445096960
1403638206495097088
1403638206545096960
1403638206595097088
1403638206645096960
1403638206695097088
1403638206745096960
1403638206795097088
1403638206845096960
1403638206895097088
1403638206945096960
1403638206995097088
1403638207045096960
1403638207095097088
1403638207145096960
1403638207195097088
1403638207245096960
1403638207295097088
1403638207345096960
1403638207395097088
1403638207445096960
1403638207495097088
1403638207545096960
1403638207595097088
1403638207645096960
1403638207695097088
1403638207745096960
1403638207795097088
1403638207845096960
1403638207895097088
1403638207945096960
1403638207995097088
1403638208045096960
1403638208095097088
1403638208145096960
1403638208195097088
1403638208245096960
1403638208295097088
1403638208345096960
1403638208395097088
1403638208445096960
1403638208495097088
1403638208545096960
1403638208595097088
1403638208645096960
1403638208695097088
1403638208745096960
1403638208795097088
1403638208845096960
1403638208895097088
1403638208945096960
1403638208995097088
1403638209045096960
1403638209095097088
1403638209145096960
1403638209195097088
1403638209245096960
1403638209295097088
1403638209345096960
1403638209395097088
1403638209445096960
1403638209495097088
1403638209545096960
1403638209595097088
1403638209645096960
1403638209695097088
1403638209745096960
1403638209795097088
1403638209845096960
1403638209895097088
1403638209945096960
1403638209995097088
1403638210045096960
1403638210095097088
1403638210145096960
1403638210195097088
1403638210245096960
1403638210295097088
1403638210345096960
1403638210395097088
1403638210445096960
1403638210495097088
1403638210545096960
1403638210595097088
1403638210645096960
1403638210695097088
1403638210745096960
1403638210795097088
1403638210845096960
1403638210895097088
1403638210945096960
1403638210995097088
1403638211045096960
1403638211095097088
1403638211145096960
1403638211195097088
1403638211245096960
1403638211295097088
1403638211345096960
1403638211395097088
1403638211445096960
1403638211495097088
1403638211545096960
1403638211595097088
1403638211645096960
1403638211695097088
1403638211745096960
1403638211795097088
1403638211845096960
1403638211895097088
1403638211945096960
1403638211995097088
1403638212045096960
1403638212095097088
1403638212145096960
1403638212195097088
1403638212245096960
1403638212295097088
1403638212345096960
1403638212395097088
1403638212445096960
1403638212495097088
1403638212545096960
1403638212595097088
1403638212645096960
1403638212695097088
1403638212745096960
1403638212795097088
1403638212845096960
1403638212895097088
1403638212945096960
1403638212995097088
1403638213045096960
1403638213095097088
1403638213145096960
1403638213195097088
1403638213245096960
1403638213295097088
1403638213345096960
1403638213395097088
1403638213445096960
1403638213495097088
1403638213545096960
1403638213595097088
1403638213645096960
1403638213695097088
1403638213745096960
1403638213795097088
1403638213845096960
1403638213895097088
1403638213945096960
1403638213995097088
1403638214045096960
1403638214095097088
1403638214145096960
1403638214195097088
1403638214245096960
1403638214295097088
1403638214345096960
1403638214395097088
1403638214445096960
1403638214495097088
1403638214545096960
1403638214595097088
1403638214645096960
1403638214695097088
1403638214745096960
1403638214795097088
1403638214845096960
1403638214895097088
1403638214945096960
1403638214995097088
1403638215045096960
1403638215095097088
1403638215145096960
1403638215195097088
1403638215245096960
1403638215295097088
1403638215345096960
1403638215395097088
1403638215445096960
1403638215495097088
1403638215545096960
1403638215595097088
1403638215645096960
1403638215695097088
1403638215745096960
1403638215795097088
1403638215845096960
1403638215895097088
1403638215945096960
1403638215995097088
1403638216045096960
1403638216095097088
1403638216145096960
1403638216195097088
1403638216245096960
1403638216295097088
1403638216345096960
1403638216395097088
1403638216445096960
1403638216495097088
1403638216545096960
1403638216595097088
1403638216645096960
1403638216695097088
1403638216745096960
1403638216795097088
1403638216845096960
1403638216895097088
1403638216945096960
1403638216995097088
1403638217045096960
1403638217095097088
1403638217145096960
1403638217195097088
1403638217245096960
1403638217295097088
1403638217345096960
1403638217395097088
1403638217445096960
1403638217495097088
1403638217545096960
1403638217595097088
1403638217645096960
1403638217695097088
1403638217745096960
1403638217795097088
1403638217845096960
1403638217895097088
1403638217945096960
1403638217995097088
1403638218045096960
1403638218095097088
1403638218145096960
1403638218195097088
1403638218245096960
1403638218295097088
1403638218345096960
1403638218395097088
1403638218445096960
1403638218495097088
1403638218545096960
1403638218595097088
1403638218645096960
1403638218695097088
1403638218745096960
1403638218795097088
1403638218845096960
1403638218895097088
1403638218945096960
1403638218995097088
1403638219045096960
1403638219095097088
1403638219145096960
1403638219195097088
1403638219245096960
1403638219295097088
1403638219345096960
1403638219395097088
1403638219445096960
1403638219495097088
1403638219545096960
1403638219595097088
1403638219645096960
1403638219695097088
1403638219745096960
1403638219795097088
1403638219845096960
1403638219895097088
1403638219945096960
1403638219995097088
1403638220045096960
1403638220095097088
1403638220145096960
1403638220195097088
1403638220245096960
1403638220295097088
1403638220345096960
1403638220395097088
1403638220445096960
1403638220495097088
1403638220545096960
1403638220595097088
1403638220645096960
1403638220695097088
1403638220745096960
1403638220795097088
1403638220845096960
1403638220895097088
1403638220945096960
1403638220995097088
1403638221045096960
1403638221095097088
1403638221145096960
1403638221195097088
1403638221245096960
1403638221295097088
1403638221345096960
1403638221395097088
1403638221445096960
1403638221495097088
1403638221545096960
1403638221595097088
1403638221645096960
1403638221695097088
1403638221745096960
1403638221795097088
1403638221845096960
1403638221895097088
1403638221945096960
1403638221995097088
1403638222045096960
1403638222095097088
1403638222145096960
1403638222195097088
1403638222245096960
1403638222295097088
1403638222345096960
1403638222395097088
1403638222445096960
1403638222495097088
1403638222545096960
1403638222595097088
1403638222645096960
1403638222695097088
1403638222745096960
1403638222795097088
1403638222845096960
1403638222895097088
1403638222945096960
1403638222995097088
1403638223045096960
1403638223095097088
1403638223145096960
1403638223195097088
1403638223245096960
1403638223295097088
1403638223345096960
1403638223395097088
1403638223445096960
1403638223495097088
1403638223545096960
1403638223595097088
1403638223645096960
1403638223695097088
1403638223745096960
1403638223795097088
1403638223845096960
1403638223895097088
1403638223945096960
1403638223995097088
1403638224045096960
1403638224095097088
1403638224145096960
1403638224195097088
1403638224245096960
1403638224295097088
1403638224345096960
1403638224395097088
1403638224445096960
1403638224495097088
1403638224545096960
1403638224595097088
1403638224645096960
1403638224695097088
1403638224745096960
1403638224795097088
1403638224845096960
1403638224895097088
1403638224945096960
1403638224995097088
1403638225045096960
1403638225095097088
1403638225145096960
1403638225195097088
1403638225245096960
1403638225295097088
1403638225345096960
1403638225395097088
1403638225445096960
1403638225495097088
1403638225545096960
1403638225595097088
1403638225645096960
1403638225695097088
1403638225745096960
1403638225795097088
1403638225845096960
1403638225895097088
1403638225945096960
1403638225995097088
1403638226045096960
1403638226095097088
1403638226145096960
1403638226195097088
1403638226245096960
1403638226295097088
1403638226345096960
1403638226395097088
1403638226445096960
1403638226495097088
1403638226545096960
1403638226595097088
1403638226645096960
1403638226695097088
1403638226745096960
1403638226795097088
1403638226845096960
1403638226895097088
1403638226945096960
1403638226995097088
1403638227045096960
1403638227095097088
1403638227145096960
1403638227195097088
1403638227245096960
1403638227295097088
1403638227345096960
1403638227395097088
1403638227445096960
1403638227495097088
1403638227545096960
1403638227595097088
1403638227645096960
1403638227695097088
1403638227745096960
1403638227795097088
1403638227845096960
1403638227895097088
1403638227945096960
1403638227995097088
1403638228045096960
1403638228095097088
1403638228145096960
1403638228195097088
1403638228245096960
1403638228295097088
1403638228345096960
1403638228395097088
1403638228445096960
1403638228495097088
1403638228545096960
1403638228595097088
1403638228645096960
1403638228695097088
1403638228745096960
1403638228795097088
1403638228845096960
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/MH05.txt
================================================
1403638518077829376
1403638518127829504
1403638518177829376
1403638518227829504
1403638518277829376
1403638518327829504
1403638518377829376
1403638518427829504
1403638518477829376
1403638518527829504
1403638518577829376
1403638518627829504
1403638518677829376
1403638518727829504
1403638518777829376
1403638518827829504
1403638518877829376
1403638518927829504
1403638518977829376
1403638519027829504
1403638519077829376
1403638519127829504
1403638519177829376
1403638519227829504
1403638519277829376
1403638519327829504
1403638519377829376
1403638519427829504
1403638519477829376
1403638519527829504
1403638519577829376
1403638519627829504
1403638519677829376
1403638519727829504
1403638519777829376
1403638519827829504
1403638519877829376
1403638519927829504
1403638519977829376
1403638520027829504
1403638520077829376
1403638520127829504
1403638520177829376
1403638520227829504
1403638520277829376
1403638520327829504
1403638520377829376
1403638520427829504
1403638520477829376
1403638520527829504
1403638520577829376
1403638520627829504
1403638520677829376
1403638520727829504
1403638520777829376
1403638520827829504
1403638520877829376
1403638520927829504
1403638520977829376
1403638521027829504
1403638521077829376
1403638521127829504
1403638521177829376
1403638521227829504
1403638521277829376
1403638521327829504
1403638521377829376
1403638521427829504
1403638521477829376
1403638521527829504
1403638521577829376
1403638521627829504
1403638521677829376
1403638521727829504
1403638521777829376
1403638521827829504
1403638521877829376
1403638521927829504
1403638521977829376
1403638522027829504
1403638522077829376
1403638522127829504
1403638522177829376
1403638522227829504
1403638522277829376
1403638522327829504
1403638522377829376
1403638522427829504
1403638522477829376
1403638522527829504
1403638522577829376
1403638522627829504
1403638522677829376
1403638522727829504
1403638522777829376
1403638522827829504
1403638522877829376
1403638522927829504
1403638522977829376
1403638523027829504
1403638523077829376
1403638523127829504
1403638523177829376
1403638523227829504
1403638523277829376
1403638523327829504
1403638523377829376
1403638523427829504
1403638523477829376
1403638523527829504
1403638523577829376
1403638523627829504
1403638523677829376
1403638523727829504
1403638523777829376
1403638523827829504
1403638523877829376
1403638523927829504
1403638523977829376
1403638524027829504
1403638524077829376
1403638524127829504
1403638524177829376
1403638524227829504
1403638524277829376
1403638524327829504
1403638524377829376
1403638524427829504
1403638524477829376
1403638524527829504
1403638524577829376
1403638524627829504
1403638524677829376
1403638524727829504
1403638524777829376
1403638524827829504
1403638524877829376
1403638524927829504
1403638524977829376
1403638525027829504
1403638525077829376
1403638525127829504
1403638525177829376
1403638525227829504
1403638525277829376
1403638525327829504
1403638525377829376
1403638525427829504
1403638525477829376
1403638525527829504
1403638525577829376
1403638525627829504
1403638525677829376
1403638525727829504
1403638525777829376
1403638525827829504
1403638525877829376
1403638525927829504
1403638525977829376
1403638526027829504
1403638526077829376
1403638526127829504
1403638526177829376
1403638526227829504
1403638526277829376
1403638526327829504
1403638526377829376
1403638526427829504
1403638526477829376
1403638526527829504
1403638526577829376
1403638526627829504
1403638526677829376
1403638526727829504
1403638526777829376
1403638526827829504
1403638526877829376
1403638526927829504
1403638526977829376
1403638527027829504
1403638527077829376
1403638527127829504
1403638527177829376
1403638527227829504
1403638527277829376
1403638527327829504
1403638527377829376
1403638527427829504
1403638527477829376
1403638527527829504
1403638527577829376
1403638527627829504
1403638527677829376
1403638527727829504
1403638527777829376
1403638527827829504
1403638527877829376
1403638527927829504
1403638527977829376
1403638528027829504
1403638528077829376
1403638528127829504
1403638528177829376
1403638528227829504
1403638528277829376
1403638528327829504
1403638528377829376
1403638528427829504
1403638528477829376
1403638528527829504
1403638528577829376
1403638528627829504
1403638528677829376
1403638528727829504
1403638528777829376
1403638528827829504
1403638528877829376
1403638528927829504
1403638528977829376
1403638529027829504
1403638529077829376
1403638529127829504
1403638529177829376
1403638529227829504
1403638529277829376
1403638529327829504
1403638529377829376
1403638529427829504
1403638529477829376
1403638529527829504
1403638529577829376
1403638529627829504
1403638529677829376
1403638529727829504
1403638529777829376
1403638529827829504
1403638529877829376
1403638529927829504
1403638529977829376
1403638530027829504
1403638530077829376
1403638530127829504
1403638530177829376
1403638530227829504
1403638530277829376
1403638530327829504
1403638530377829376
1403638530427829504
1403638530477829376
1403638530527829504
1403638530577829376
1403638530627829504
1403638530677829376
1403638530727829504
1403638530777829376
1403638530827829504
1403638530877829376
1403638530927829504
1403638530977829376
1403638531027829504
1403638531077829376
1403638531127829504
1403638531177829376
1403638531227829504
1403638531277829376
1403638531327829504
1403638531377829376
1403638531427829504
1403638531477829376
1403638531527829504
1403638531577829376
1403638531627829504
1403638531677829376
1403638531727829504
1403638531777829376
1403638531827829504
1403638531877829376
1403638531927829504
1403638531977829376
1403638532027829504
1403638532077829376
1403638532127829504
1403638532177829376
1403638532227829504
1403638532277829376
1403638532327829504
1403638532377829376
1403638532427829504
1403638532477829376
1403638532527829504
1403638532577829376
1403638532627829504
1403638532677829376
1403638532727829504
1403638532777829376
1403638532827829504
1403638532877829376
1403638532927829504
1403638532977829376
1403638533027829504
1403638533077829376
1403638533127829504
1403638533177829376
1403638533227829504
1403638533277829376
1403638533327829504
1403638533377829376
1403638533427829504
1403638533477829376
1403638533527829504
1403638533577829376
1403638533627829504
1403638533677829376
1403638533727829504
1403638533777829376
1403638533827829504
1403638533877829376
1403638533927829504
1403638533977829376
1403638534027829504
1403638534077829376
1403638534127829504
1403638534177829376
1403638534227829504
1403638534277829376
1403638534327829504
1403638534377829376
1403638534427829504
1403638534477829376
1403638534527829504
1403638534577829376
1403638534627829504
1403638534677829376
1403638534727829504
1403638534777829376
1403638534827829504
1403638534877829376
1403638534927829504
1403638534977829376
1403638535027829504
1403638535077829376
1403638535127829504
1403638535177829376
1403638535227829504
1403638535277829376
1403638535327829504
1403638535377829376
1403638535427829504
1403638535477829376
1403638535527829504
1403638535577829376
1403638535627829504
1403638535677829376
1403638535727829504
1403638535777829376
1403638535827829504
1403638535877829376
1403638535927829504
1403638535977829376
1403638536027829504
1403638536077829376
1403638536127829504
1403638536177829376
1403638536227829504
1403638536277829376
1403638536327829504
1403638536377829376
1403638536427829504
1403638536477829376
1403638536527829504
1403638536577829376
1403638536627829504
1403638536677829376
1403638536727829504
1403638536777829376
1403638536827829504
1403638536877829376
1403638536927829504
1403638536977829376
1403638537027829504
1403638537077829376
1403638537127829504
1403638537177829376
1403638537227829504
1403638537277829376
1403638537327829504
1403638537377829376
1403638537427829504
1403638537477829376
1403638537527829504
1403638537577829376
1403638537627829504
1403638537677829376
1403638537727829504
1403638537777829376
1403638537827829504
1403638537877829376
1403638537927829504
1403638537977829376
1403638538027829504
1403638538077829376
1403638538127829504
1403638538177829376
1403638538227829504
1403638538277829376
1403638538327829504
1403638538377829376
1403638538427829504
1403638538477829376
1403638538527829504
1403638538577829376
1403638538627829504
1403638538677829376
1403638538727829504
1403638538777829376
1403638538827829504
1403638538877829376
1403638538927829504
1403638538977829376
1403638539027829504
1403638539077829376
1403638539127829504
1403638539177829376
1403638539227829504
1403638539277829376
1403638539327829504
1403638539377829376
1403638539427829504
1403638539477829376
1403638539527829504
1403638539577829376
1403638539627829504
1403638539677829376
1403638539727829504
1403638539777829376
1403638539827829504
1403638539877829376
1403638539927829504
1403638539977829376
1403638540027829504
1403638540077829376
1403638540127829504
1403638540177829376
1403638540227829504
1403638540277829376
1403638540327829504
1403638540377829376
1403638540427829504
1403638540477829376
1403638540527829504
1403638540577829376
1403638540627829504
1403638540677829376
1403638540727829504
1403638540777829376
1403638540827829504
1403638540877829376
1403638540927829504
1403638540977829376
1403638541027829504
1403638541077829376
1403638541127829504
1403638541177829376
1403638541227829504
1403638541277829376
1403638541327829504
1403638541377829376
1403638541427829504
1403638541477829376
1403638541527829504
1403638541577829376
1403638541627829504
1403638541677829376
1403638541727829504
1403638541777829376
1403638541827829504
1403638541877829376
1403638541927829504
1403638541977829376
1403638542027829504
1403638542077829376
1403638542127829504
1403638542177829376
1403638542227829504
1403638542277829376
1403638542327829504
1403638542377829376
1403638542427829504
1403638542477829376
1403638542527829504
1403638542577829376
1403638542627829504
1403638542677829376
1403638542727829504
1403638542777829376
1403638542827829504
1403638542877829376
1403638542927829504
1403638542977829376
1403638543027829504
1403638543077829376
1403638543127829504
1403638543177829376
1403638543227829504
1403638543277829376
1403638543327829504
1403638543377829376
1403638543427829504
1403638543477829376
1403638543527829504
1403638543577829376
1403638543627829504
1403638543677829376
1403638543727829504
1403638543777829376
1403638543827829504
1403638543877829376
1403638543927829504
1403638543977829376
1403638544027829504
1403638544077829376
1403638544127829504
1403638544177829376
1403638544227829504
1403638544277829376
1403638544327829504
1403638544377829376
1403638544427829504
1403638544477829376
1403638544527829504
1403638544577829376
1403638544627829504
1403638544677829376
1403638544727829504
1403638544777829376
1403638544827829504
1403638544877829376
1403638544927829504
1403638544977829376
1403638545027829504
1403638545077829376
1403638545127829504
1403638545177829376
1403638545227829504
1403638545277829376
1403638545327829504
1403638545377829376
1403638545427829504
1403638545477829376
1403638545527829504
1403638545577829376
1403638545627829504
1403638545677829376
1403638545727829504
1403638545777829376
1403638545827829504
1403638545877829376
1403638545927829504
1403638545977829376
1403638546027829504
1403638546077829376
1403638546127829504
1403638546177829376
1403638546227829504
1403638546277829376
1403638546327829504
1403638546377829376
1403638546427829504
1403638546477829376
1403638546527829504
1403638546577829376
1403638546627829504
1403638546677829376
1403638546727829504
1403638546777829376
1403638546827829504
1403638546877829376
1403638546927829504
1403638546977829376
1403638547027829504
1403638547077829376
1403638547127829504
1403638547177829376
1403638547227829504
1403638547277829376
1403638547327829504
1403638547377829376
1403638547427829504
1403638547477829376
1403638547527829504
1403638547577829376
1403638547627829504
1403638547677829376
1403638547727829504
1403638547777829376
1403638547827829504
1403638547877829376
1403638547927829504
1403638547977829376
1403638548027829504
1403638548077829376
1403638548127829504
1403638548177829376
1403638548227829504
1403638548277829376
1403638548327829504
1403638548377829376
1403638548427829504
1403638548477829376
1403638548527829504
1403638548577829376
1403638548627829504
1403638548677829376
1403638548727829504
1403638548777829376
1403638548827829504
1403638548877829376
1403638548927829504
1403638548977829376
1403638549027829504
1403638549077829376
1403638549127829504
1403638549177829376
1403638549227829504
1403638549277829376
1403638549327829504
1403638549377829376
1403638549427829504
1403638549477829376
1403638549527829504
1403638549577829376
1403638549627829504
1403638549677829376
1403638549727829504
1403638549777829376
1403638549827829504
1403638549877829376
1403638549927829504
1403638549977829376
1403638550027829504
1403638550077829376
1403638550127829504
1403638550177829376
1403638550227829504
1403638550277829376
1403638550327829504
1403638550377829376
1403638550427829504
1403638550477829376
1403638550527829504
1403638550577829376
1403638550627829504
1403638550677829376
1403638550727829504
1403638550777829376
1403638550827829504
1403638550877829376
1403638550927829504
1403638550977829376
1403638551027829504
1403638551077829376
1403638551127829504
1403638551177829376
1403638551227829504
1403638551277829376
1403638551327829504
1403638551377829376
1403638551427829504
1403638551477829376
1403638551527829504
1403638551577829376
1403638551627829504
1403638551677829376
1403638551727829504
1403638551777829376
1403638551827829504
1403638551877829376
1403638551927829504
1403638551977829376
1403638552027829504
1403638552077829376
1403638552127829504
1403638552177829376
1403638552227829504
1403638552277829376
1403638552327829504
1403638552377829376
1403638552427829504
1403638552477829376
1403638552527829504
1403638552577829376
1403638552627829504
1403638552677829376
1403638552727829504
1403638552777829376
1403638552827829504
1403638552877829376
1403638552927829504
1403638552977829376
1403638553027829504
1403638553077829376
1403638553127829504
1403638553177829376
1403638553227829504
1403638553277829376
1403638553327829504
1403638553377829376
1403638553427829504
1403638553477829376
1403638553527829504
1403638553577829376
1403638553627829504
1403638553677829376
1403638553727829504
1403638553777829376
1403638553827829504
1403638553877829376
1403638553927829504
1403638553977829376
1403638554027829504
1403638554077829376
1403638554127829504
1403638554177829376
1403638554227829504
1403638554277829376
1403638554327829504
1403638554377829376
1403638554427829504
1403638554477829376
1403638554527829504
1403638554577829376
1403638554627829504
1403638554677829376
1403638554727829504
1403638554777829376
1403638554827829504
1403638554877829376
1403638554927829504
1403638554977829376
1403638555027829504
1403638555077829376
1403638555127829504
1403638555177829376
1403638555227829504
1403638555277829376
1403638555327829504
1403638555377829376
1403638555427829504
1403638555477829376
1403638555527829504
1403638555577829376
1403638555627829504
1403638555677829376
1403638555727829504
1403638555777829376
1403638555827829504
1403638555877829376
1403638555927829504
1403638555977829376
1403638556027829504
1403638556077829376
1403638556127829504
1403638556177829376
1403638556227829504
1403638556277829376
1403638556327829504
1403638556377829376
1403638556427829504
1403638556477829376
1403638556527829504
1403638556577829376
1403638556627829504
1403638556677829376
1403638556727829504
1403638556777829376
1403638556827829504
1403638556877829376
1403638556927829504
1403638556977829376
1403638557027829504
1403638557077829376
1403638557127829504
1403638557177829376
1403638557227829504
1403638557277829376
1403638557327829504
1403638557377829376
1403638557427829504
1403638557477829376
1403638557527829504
1403638557577829376
1403638557627829504
1403638557677829376
1403638557727829504
1403638557777829376
1403638557827829504
1403638557877829376
1403638557927829504
1403638557977829376
1403638558027829504
1403638558077829376
1403638558127829504
1403638558177829376
1403638558227829504
1403638558277829376
1403638558327829504
1403638558377829376
1403638558427829504
1403638558477829376
1403638558527829504
1403638558577829376
1403638558627829504
1403638558677829376
1403638558727829504
1403638558777829376
1403638558827829504
1403638558877829376
1403638558927829504
1403638558977829376
1403638559027829504
1403638559077829376
1403638559127829504
1403638559177829376
1403638559227829504
1403638559277829376
1403638559327829504
1403638559377829376
1403638559427829504
1403638559477829376
1403638559527829504
1403638559577829376
1403638559627829504
1403638559677829376
1403638559727829504
1403638559777829376
1403638559827829504
1403638559877829376
1403638559927829504
1403638559977829376
1403638560027829504
1403638560077829376
1403638560127829504
1403638560177829376
1403638560227829504
1403638560277829376
1403638560327829504
1403638560377829376
1403638560427829504
1403638560477829376
1403638560527829504
1403638560577829376
1403638560627829504
1403638560677829376
1403638560727829504
1403638560777829376
1403638560827829504
1403638560877829376
1403638560927829504
1403638560977829376
1403638561027829504
1403638561077829376
1403638561127829504
1403638561177829376
1403638561227829504
1403638561277829376
1403638561327829504
1403638561377829376
1403638561427829504
1403638561477829376
1403638561527829504
1403638561577829376
1403638561627829504
1403638561677829376
1403638561727829504
1403638561777829376
1403638561827829504
1403638561877829376
1403638561927829504
1403638561977829376
1403638562027829504
1403638562077829376
1403638562127829504
1403638562177829376
1403638562227829504
1403638562277829376
1403638562327829504
1403638562377829376
1403638562427829504
1403638562477829376
1403638562527829504
1403638562577829376
1403638562627829504
1403638562677829376
1403638562727829504
1403638562777829376
1403638562827829504
1403638562877829376
1403638562927829504
1403638562977829376
1403638563027829504
1403638563077829376
1403638563127829504
1403638563177829376
1403638563227829504
1403638563277829376
1403638563327829504
1403638563377829376
1403638563427829504
1403638563477829376
1403638563527829504
1403638563577829376
1403638563627829504
1403638563677829376
1403638563727829504
1403638563777829376
1403638563827829504
1403638563877829376
1403638563927829504
1403638563977829376
1403638564027829504
1403638564077829376
1403638564127829504
1403638564177829376
1403638564227829504
1403638564277829376
1403638564327829504
1403638564377829376
1403638564427829504
1403638564477829376
1403638564527829504
1403638564577829376
1403638564627829504
1403638564677829376
1403638564727829504
1403638564777829376
1403638564827829504
1403638564877829376
1403638564927829504
1403638564977829376
1403638565027829504
1403638565077829376
1403638565127829504
1403638565177829376
1403638565227829504
1403638565277829376
1403638565327829504
1403638565377829376
1403638565427829504
1403638565477829376
1403638565527829504
1403638565577829376
1403638565627829504
1403638565677829376
1403638565727829504
1403638565777829376
1403638565827829504
1403638565877829376
1403638565927829504
1403638565977829376
1403638566027829504
1403638566077829376
1403638566127829504
1403638566177829376
1403638566227829504
1403638566277829376
1403638566327829504
1403638566377829376
1403638566427829504
1403638566477829376
1403638566527829504
1403638566577829376
1403638566627829504
1403638566677829376
1403638566727829504
1403638566777829376
1403638566827829504
1403638566877829376
1403638566927829504
1403638566977829376
1403638567027829504
1403638567077829376
1403638567127829504
1403638567177829376
1403638567227829504
1403638567277829376
1403638567327829504
1403638567377829376
1403638567427829504
1403638567477829376
1403638567527829504
1403638567577829376
1403638567627829504
1403638567677829376
1403638567727829504
1403638567777829376
1403638567827829504
1403638567877829376
1403638567927829504
1403638567977829376
1403638568027829504
1403638568077829376
1403638568127829504
1403638568177829376
1403638568227829504
1403638568277829376
1403638568327829504
1403638568377829376
1403638568427829504
1403638568477829376
1403638568527829504
1403638568577829376
1403638568627829504
1403638568677829376
1403638568727829504
1403638568777829376
1403638568827829504
1403638568877829376
1403638568927829504
1403638568977829376
1403638569027829504
1403638569077829376
1403638569127829504
1403638569177829376
1403638569227829504
1403638569277829376
1403638569327829504
1403638569377829376
1403638569427829504
1403638569477829376
1403638569527829504
1403638569577829376
1403638569627829504
1403638569677829376
1403638569727829504
1403638569777829376
1403638569827829504
1403638569877829376
1403638569927829504
1403638569977829376
1403638570027829504
1403638570077829376
1403638570127829504
1403638570177829376
1403638570227829504
1403638570277829376
1403638570327829504
1403638570377829376
1403638570427829504
1403638570477829376
1403638570527829504
1403638570577829376
1403638570627829504
1403638570677829376
1403638570727829504
1403638570777829376
1403638570827829504
1403638570877829376
1403638570927829504
1403638570977829376
1403638571027829504
1403638571077829376
1403638571127829504
1403638571177829376
1403638571227829504
1403638571277829376
1403638571327829504
1403638571377829376
1403638571427829504
1403638571477829376
1403638571527829504
1403638571577829376
1403638571627829504
1403638571677829376
1403638571727829504
1403638571777829376
1403638571827829504
1403638571877829376
1403638571927829504
1403638571977829376
1403638572027829504
1403638572077829376
1403638572127829504
1403638572177829376
1403638572227829504
1403638572277829376
1403638572327829504
1403638572377829376
1403638572427829504
1403638572477829376
1403638572527829504
1403638572577829376
1403638572627829504
1403638572677829376
1403638572727829504
1403638572777829376
1403638572827829504
1403638572877829376
1403638572927829504
1403638572977829376
1403638573027829504
1403638573077829376
1403638573127829504
1403638573177829376
1403638573227829504
1403638573277829376
1403638573327829504
1403638573377829376
1403638573427829504
1403638573477829376
1403638573527829504
1403638573577829376
1403638573627829504
1403638573677829376
1403638573727829504
1403638573777829376
1403638573827829504
1403638573877829376
1403638573927829504
1403638573977829376
1403638574027829504
1403638574077829376
1403638574127829504
1403638574177829376
1403638574227829504
1403638574277829376
1403638574327829504
1403638574377829376
1403638574427829504
1403638574477829376
1403638574527829504
1403638574577829376
1403638574627829504
1403638574677829376
1403638574727829504
1403638574777829376
1403638574827829504
1403638574877829376
1403638574927829504
1403638574977829376
1403638575027829504
1403638575077829376
1403638575127829504
1403638575177829376
1403638575227829504
1403638575277829376
1403638575327829504
1403638575377829376
1403638575427829504
1403638575477829376
1403638575527829504
1403638575577829376
1403638575627829504
1403638575677829376
1403638575727829504
1403638575777829376
1403638575827829504
1403638575877829376
1403638575927829504
1403638575977829376
1403638576027829504
1403638576077829376
1403638576127829504
1403638576177829376
1403638576227829504
1403638576277829376
1403638576327829504
1403638576377829376
1403638576427829504
1403638576477829376
1403638576527829504
1403638576577829376
1403638576627829504
1403638576677829376
1403638576727829504
1403638576777829376
1403638576827829504
1403638576877829376
1403638576927829504
1403638576977829376
1403638577027829504
1403638577077829376
1403638577127829504
1403638577177829376
1403638577227829504
1403638577277829376
1403638577327829504
1403638577377829376
1403638577427829504
1403638577477829376
1403638577527829504
1403638577577829376
1403638577627829504
1403638577677829376
1403638577727829504
1403638577777829376
1403638577827829504
1403638577877829376
1403638577927829504
1403638577977829376
1403638578027829504
1403638578077829376
1403638578127829504
1403638578177829376
1403638578227829504
1403638578277829376
1403638578327829504
1403638578377829376
1403638578427829504
1403638578477829376
1403638578527829504
1403638578577829376
1403638578627829504
1403638578677829376
1403638578727829504
1403638578777829376
1403638578827829504
1403638578877829376
1403638578927829504
1403638578977829376
1403638579027829504
1403638579077829376
1403638579127829504
1403638579177829376
1403638579227829504
1403638579277829376
1403638579327829504
1403638579377829376
1403638579427829504
1403638579477829376
1403638579527829504
1403638579577829376
1403638579627829504
1403638579677829376
1403638579727829504
1403638579777829376
1403638579827829504
1403638579877829376
1403638579927829504
1403638579977829376
1403638580027829504
1403638580077829376
1403638580127829504
1403638580177829376
1403638580227829504
1403638580277829376
1403638580327829504
1403638580377829376
1403638580427829504
1403638580477829376
1403638580527829504
1403638580577829376
1403638580627829504
1403638580677829376
1403638580727829504
1403638580777829376
1403638580827829504
1403638580877829376
1403638580927829504
1403638580977829376
1403638581027829504
1403638581077829376
1403638581127829504
1403638581177829376
1403638581227829504
1403638581277829376
1403638581327829504
1403638581377829376
1403638581427829504
1403638581477829376
1403638581527829504
1403638581577829376
1403638581627829504
1403638581677829376
1403638581727829504
1403638581777829376
1403638581827829504
1403638581877829376
1403638581927829504
1403638581977829376
1403638582027829504
1403638582077829376
1403638582127829504
1403638582177829376
1403638582227829504
1403638582277829376
1403638582327829504
1403638582377829376
1403638582427829504
1403638582477829376
1403638582527829504
1403638582577829376
1403638582627829504
1403638582677829376
1403638582727829504
1403638582777829376
1403638582827829504
1403638582877829376
1403638582927829504
1403638582977829376
1403638583027829504
1403638583077829376
1403638583127829504
1403638583177829376
1403638583227829504
1403638583277829376
1403638583327829504
1403638583377829376
1403638583427829504
1403638583477829376
1403638583527829504
1403638583577829376
1403638583627829504
1403638583677829376
1403638583727829504
1403638583777829376
1403638583827829504
1403638583877829376
1403638583927829504
1403638583977829376
1403638584027829504
1403638584077829376
1403638584127829504
1403638584177829376
1403638584227829504
1403638584277829376
1403638584327829504
1403638584377829376
1403638584427829504
1403638584477829376
1403638584527829504
1403638584577829376
1403638584627829504
1403638584677829376
1403638584727829504
1403638584777829376
1403638584827829504
1403638584877829376
1403638584927829504
1403638584977829376
1403638585027829504
1403638585077829376
1403638585127829504
1403638585177829376
1403638585227829504
1403638585277829376
1403638585327829504
1403638585377829376
1403638585427829504
1403638585477829376
1403638585527829504
1403638585577829376
1403638585627829504
1403638585677829376
1403638585727829504
1403638585777829376
1403638585827829504
1403638585877829376
1403638585927829504
1403638585977829376
1403638586027829504
1403638586077829376
1403638586127829504
1403638586177829376
1403638586227829504
1403638586277829376
1403638586327829504
1403638586377829376
1403638586427829504
1403638586477829376
1403638586527829504
1403638586577829376
1403638586627829504
1403638586677829376
1403638586727829504
1403638586777829376
1403638586827829504
1403638586877829376
1403638586927829504
1403638586977829376
1403638587027829504
1403638587077829376
1403638587127829504
1403638587177829376
1403638587227829504
1403638587277829376
1403638587327829504
1403638587377829376
1403638587427829504
1403638587477829376
1403638587527829504
1403638587577829376
1403638587627829504
1403638587677829376
1403638587727829504
1403638587777829376
1403638587827829504
1403638587877829376
1403638587927829504
1403638587977829376
1403638588027829504
1403638588077829376
1403638588127829504
1403638588177829376
1403638588227829504
1403638588277829376
1403638588327829504
1403638588377829376
1403638588427829504
1403638588477829376
1403638588527829504
1403638588577829376
1403638588627829504
1403638588677829376
1403638588727829504
1403638588777829376
1403638588827829504
1403638588877829376
1403638588927829504
1403638588977829376
1403638589027829504
1403638589077829376
1403638589127829504
1403638589177829376
1403638589227829504
1403638589277829376
1403638589327829504
1403638589377829376
1403638589427829504
1403638589477829376
1403638589527829504
1403638589577829376
1403638589627829504
1403638589677829376
1403638589727829504
1403638589777829376
1403638589827829504
1403638589877829376
1403638589927829504
1403638589977829376
1403638590027829504
1403638590077829376
1403638590127829504
1403638590177829376
1403638590227829504
1403638590277829376
1403638590327829504
1403638590377829376
1403638590427829504
1403638590477829376
1403638590527829504
1403638590577829376
1403638590627829504
1403638590677829376
1403638590727829504
1403638590777829376
1403638590827829504
1403638590877829376
1403638590927829504
1403638590977829376
1403638591027829504
1403638591077829376
1403638591127829504
1403638591177829376
1403638591227829504
1403638591277829376
1403638591327829504
1403638591377829376
1403638591427829504
1403638591477829376
1403638591527829504
1403638591577829376
1403638591627829504
1403638591677829376
1403638591727829504
1403638591777829376
1403638591827829504
1403638591877829376
1403638591927829504
1403638591977829376
1403638592027829504
1403638592077829376
1403638592127829504
1403638592177829376
1403638592227829504
1403638592277829376
1403638592327829504
1403638592377829376
1403638592427829504
1403638592477829376
1403638592527829504
1403638592577829376
1403638592627829504
1403638592677829376
1403638592727829504
1403638592777829376
1403638592827829504
1403638592877829376
1403638592927829504
1403638592977829376
1403638593027829504
1403638593077829376
1403638593127829504
1403638593177829376
1403638593227829504
1403638593277829376
1403638593327829504
1403638593377829376
1403638593427829504
1403638593477829376
1403638593527829504
1403638593577829376
1403638593627829504
1403638593677829376
1403638593727829504
1403638593777829376
1403638593827829504
1403638593877829376
1403638593927829504
1403638593977829376
1403638594027829504
1403638594077829376
1403638594127829504
1403638594177829376
1403638594227829504
1403638594277829376
1403638594327829504
1403638594377829376
1403638594427829504
1403638594477829376
1403638594527829504
1403638594577829376
1403638594627829504
1403638594677829376
1403638594727829504
1403638594777829376
1403638594827829504
1403638594877829376
1403638594927829504
1403638594977829376
1403638595027829504
1403638595077829376
1403638595127829504
1403638595177829376
1403638595227829504
1403638595277829376
1403638595327829504
1403638595377829376
1403638595427829504
1403638595477829376
1403638595527829504
1403638595577829376
1403638595627829504
1403638595677829376
1403638595727829504
1403638595777829376
1403638595827829504
1403638595877829376
1403638595927829504
1403638595977829376
1403638596027829504
1403638596077829376
1403638596127829504
1403638596177829376
1403638596227829504
1403638596277829376
1403638596327829504
1403638596377829376
1403638596427829504
1403638596477829376
1403638596527829504
1403638596577829376
1403638596627829504
1403638596677829376
1403638596727829504
1403638596777829376
1403638596827829504
1403638596877829376
1403638596927829504
1403638596977829376
1403638597027829504
1403638597077829376
1403638597127829504
1403638597177829376
1403638597227829504
1403638597277829376
1403638597327829504
1403638597377829376
1403638597427829504
1403638597477829376
1403638597527829504
1403638597577829376
1403638597627829504
1403638597677829376
1403638597727829504
1403638597777829376
1403638597827829504
1403638597877829376
1403638597927829504
1403638597977829376
1403638598027829504
1403638598077829376
1403638598127829504
1403638598177829376
1403638598227829504
1403638598277829376
1403638598327829504
1403638598377829376
1403638598427829504
1403638598477829376
1403638598527829504
1403638598577829376
1403638598627829504
1403638598677829376
1403638598727829504
1403638598777829376
1403638598827829504
1403638598877829376
1403638598927829504
1403638598977829376
1403638599027829504
1403638599077829376
1403638599127829504
1403638599177829376
1403638599227829504
1403638599277829376
1403638599327829504
1403638599377829376
1403638599427829504
1403638599477829376
1403638599527829504
1403638599577829376
1403638599627829504
1403638599677829376
1403638599727829504
1403638599777829376
1403638599827829504
1403638599877829376
1403638599927829504
1403638599977829376
1403638600027829504
1403638600077829376
1403638600127829504
1403638600177829376
1403638600227829504
1403638600277829376
1403638600327829504
1403638600377829376
1403638600427829504
1403638600477829376
1403638600527829504
1403638600577829376
1403638600627829504
1403638600677829376
1403638600727829504
1403638600777829376
1403638600827829504
1403638600877829376
1403638600927829504
1403638600977829376
1403638601027829504
1403638601077829376
1403638601127829504
1403638601177829376
1403638601227829504
1403638601277829376
1403638601327829504
1403638601377829376
1403638601427829504
1403638601477829376
1403638601527829504
1403638601577829376
1403638601627829504
1403638601677829376
1403638601727829504
1403638601777829376
1403638601827829504
1403638601877829376
1403638601927829504
1403638601977829376
1403638602027829504
1403638602077829376
1403638602127829504
1403638602177829376
1403638602227829504
1403638602277829376
1403638602327829504
1403638602377829376
1403638602427829504
1403638602477829376
1403638602527829504
1403638602577829376
1403638602627829504
1403638602677829376
1403638602727829504
1403638602777829376
1403638602827829504
1403638602877829376
1403638602927829504
1403638602977829376
1403638603027829504
1403638603077829376
1403638603127829504
1403638603177829376
1403638603227829504
1403638603277829376
1403638603327829504
1403638603377829376
1403638603427829504
1403638603477829376
1403638603527829504
1403638603577829376
1403638603627829504
1403638603677829376
1403638603727829504
1403638603777829376
1403638603827829504
1403638603877829376
1403638603927829504
1403638603977829376
1403638604027829504
1403638604077829376
1403638604127829504
1403638604177829376
1403638604227829504
1403638604277829376
1403638604327829504
1403638604377829376
1403638604427829504
1403638604477829376
1403638604527829504
1403638604577829376
1403638604627829504
1403638604677829376
1403638604727829504
1403638604777829376
1403638604827829504
1403638604877829376
1403638604927829504
1403638604977829376
1403638605027829504
1403638605077829376
1403638605127829504
1403638605177829376
1403638605227829504
1403638605277829376
1403638605327829504
1403638605377829376
1403638605427829504
1403638605477829376
1403638605527829504
1403638605577829376
1403638605627829504
1403638605677829376
1403638605727829504
1403638605777829376
1403638605827829504
1403638605877829376
1403638605927829504
1403638605977829376
1403638606027829504
1403638606077829376
1403638606127829504
1403638606177829376
1403638606227829504
1403638606277829376
1403638606327829504
1403638606377829376
1403638606427829504
1403638606477829376
1403638606527829504
1403638606577829376
1403638606627829504
1403638606677829376
1403638606727829504
1403638606777829376
1403638606827829504
1403638606877829376
1403638606927829504
1403638606977829376
1403638607027829504
1403638607077829376
1403638607127829504
1403638607177829376
1403638607227829504
1403638607277829376
1403638607327829504
1403638607377829376
1403638607427829504
1403638607477829376
1403638607527829504
1403638607577829376
1403638607627829504
1403638607677829376
1403638607727829504
1403638607777829376
1403638607827829504
1403638607877829376
1403638607927829504
1403638607977829376
1403638608027829504
1403638608077829376
1403638608127829504
1403638608177829376
1403638608227829504
1403638608277829376
1403638608327829504
1403638608377829376
1403638608427829504
1403638608477829376
1403638608527829504
1403638608577829376
1403638608627829504
1403638608677829376
1403638608727829504
1403638608777829376
1403638608827829504
1403638608877829376
1403638608927829504
1403638608977829376
1403638609027829504
1403638609077829376
1403638609127829504
1403638609177829376
1403638609227829504
1403638609277829376
1403638609327829504
1403638609377829376
1403638609427829504
1403638609477829376
1403638609527829504
1403638609577829376
1403638609627829504
1403638609677829376
1403638609727829504
1403638609777829376
1403638609827829504
1403638609877829376
1403638609927829504
1403638609977829376
1403638610027829504
1403638610077829376
1403638610127829504
1403638610177829376
1403638610227829504
1403638610277829376
1403638610327829504
1403638610377829376
1403638610427829504
1403638610477829376
1403638610527829504
1403638610577829376
1403638610627829504
1403638610677829376
1403638610727829504
1403638610777829376
1403638610827829504
1403638610877829376
1403638610927829504
1403638610977829376
1403638611027829504
1403638611077829376
1403638611127829504
1403638611177829376
1403638611227829504
1403638611277829376
1403638611327829504
1403638611377829376
1403638611427829504
1403638611477829376
1403638611527829504
1403638611577829376
1403638611627829504
1403638611677829376
1403638611727829504
1403638611777829376
1403638611827829504
1403638611877829376
1403638611927829504
1403638611977829376
1403638612027829504
1403638612077829376
1403638612127829504
1403638612177829376
1403638612227829504
1403638612277829376
1403638612327829504
1403638612377829376
1403638612427829504
1403638612477829376
1403638612527829504
1403638612577829376
1403638612627829504
1403638612677829376
1403638612727829504
1403638612777829376
1403638612827829504
1403638612877829376
1403638612927829504
1403638612977829376
1403638613027829504
1403638613077829376
1403638613127829504
1403638613177829376
1403638613227829504
1403638613277829376
1403638613327829504
1403638613377829376
1403638613427829504
1403638613477829376
1403638613527829504
1403638613577829376
1403638613627829504
1403638613677829376
1403638613727829504
1403638613777829376
1403638613827829504
1403638613877829376
1403638613927829504
1403638613977829376
1403638614027829504
1403638614077829376
1403638614127829504
1403638614177829376
1403638614227829504
1403638614277829376
1403638614327829504
1403638614377829376
1403638614427829504
1403638614477829376
1403638614527829504
1403638614577829376
1403638614627829504
1403638614677829376
1403638614727829504
1403638614777829376
1403638614827829504
1403638614877829376
1403638614927829504
1403638614977829376
1403638615027829504
1403638615077829376
1403638615127829504
1403638615177829376
1403638615227829504
1403638615277829376
1403638615327829504
1403638615377829376
1403638615427829504
1403638615477829376
1403638615527829504
1403638615577829376
1403638615627829504
1403638615677829376
1403638615727829504
1403638615777829376
1403638615827829504
1403638615877829376
1403638615927829504
1403638615977829376
1403638616027829504
1403638616077829376
1403638616127829504
1403638616177829376
1403638616227829504
1403638616277829376
1403638616327829504
1403638616377829376
1403638616427829504
1403638616477829376
1403638616527829504
1403638616577829376
1403638616627829504
1403638616677829376
1403638616727829504
1403638616777829376
1403638616827829504
1403638616877829376
1403638616927829504
1403638616977829376
1403638617027829504
1403638617077829376
1403638617127829504
1403638617177829376
1403638617227829504
1403638617277829376
1403638617327829504
1403638617377829376
1403638617427829504
1403638617477829376
1403638617527829504
1403638617577829376
1403638617627829504
1403638617677829376
1403638617727829504
1403638617777829376
1403638617827829504
1403638617877829376
1403638617927829504
1403638617977829376
1403638618027829504
1403638618077829376
1403638618127829504
1403638618177829376
1403638618227829504
1403638618277829376
1403638618327829504
1403638618377829376
1403638618427829504
1403638618477829376
1403638618527829504
1403638618577829376
1403638618627829504
1403638618677829376
1403638618727829504
1403638618777829376
1403638618827829504
1403638618877829376
1403638618927829504
1403638618977829376
1403638619027829504
1403638619077829376
1403638619127829504
1403638619177829376
1403638619227829504
1403638619277829376
1403638619327829504
1403638619377829376
1403638619427829504
1403638619477829376
1403638619527829504
1403638619577829376
1403638619627829504
1403638619677829376
1403638619727829504
1403638619777829376
1403638619827829504
1403638619877829376
1403638619927829504
1403638619977829376
1403638620027829504
1403638620077829376
1403638620127829504
1403638620177829376
1403638620227829504
1403638620277829376
1403638620327829504
1403638620377829376
1403638620427829504
1403638620477829376
1403638620527829504
1403638620577829376
1403638620627829504
1403638620677829376
1403638620727829504
1403638620777829376
1403638620827829504
1403638620877829376
1403638620927829504
1403638620977829376
1403638621027829504
1403638621077829376
1403638621127829504
1403638621177829376
1403638621227829504
1403638621277829376
1403638621327829504
1403638621377829376
1403638621427829504
1403638621477829376
1403638621527829504
1403638621577829376
1403638621627829504
1403638621677829376
1403638621727829504
1403638621777829376
1403638621827829504
1403638621877829376
1403638621927829504
1403638621977829376
1403638622027829504
1403638622077829376
1403638622127829504
1403638622177829376
1403638622227829504
1403638622277829376
1403638622327829504
1403638622377829376
1403638622427829504
1403638622477829376
1403638622527829504
1403638622577829376
1403638622627829504
1403638622677829376
1403638622727829504
1403638622777829376
1403638622827829504
1403638622877829376
1403638622927829504
1403638622977829376
1403638623027829504
1403638623077829376
1403638623127829504
1403638623177829376
1403638623227829504
1403638623277829376
1403638623327829504
1403638623377829376
1403638623427829504
1403638623477829376
1403638623527829504
1403638623577829376
1403638623627829504
1403638623677829376
1403638623727829504
1403638623777829376
1403638623827829504
1403638623877829376
1403638623927829504
1403638623977829376
1403638624027829504
1403638624077829376
1403638624127829504
1403638624177829376
1403638624227829504
1403638624277829376
1403638624327829504
1403638624377829376
1403638624427829504
1403638624477829376
1403638624527829504
1403638624577829376
1403638624627829504
1403638624677829376
1403638624727829504
1403638624777829376
1403638624827829504
1403638624877829376
1403638624927829504
1403638624977829376
1403638625027829504
1403638625077829376
1403638625127829504
1403638625177829376
1403638625227829504
1403638625277829376
1403638625327829504
1403638625377829376
1403638625427829504
1403638625477829376
1403638625527829504
1403638625577829376
1403638625627829504
1403638625677829376
1403638625727829504
1403638625777829376
1403638625827829504
1403638625877829376
1403638625927829504
1403638625977829376
1403638626027829504
1403638626077829376
1403638626127829504
1403638626177829376
1403638626227829504
1403638626277829376
1403638626327829504
1403638626377829376
1403638626427829504
1403638626477829376
1403638626527829504
1403638626577829376
1403638626627829504
1403638626677829376
1403638626727829504
1403638626777829376
1403638626827829504
1403638626877829376
1403638626927829504
1403638626977829376
1403638627027829504
1403638627077829376
1403638627127829504
1403638627177829376
1403638627227829504
1403638627277829376
1403638627327829504
1403638627377829376
1403638627427829504
1403638627477829376
1403638627527829504
1403638627577829376
1403638627627829504
1403638627677829376
1403638627727829504
1403638627777829376
1403638627827829504
1403638627877829376
1403638627927829504
1403638627977829376
1403638628027829504
1403638628077829376
1403638628127829504
1403638628177829376
1403638628227829504
1403638628277829376
1403638628327829504
1403638628377829376
1403638628427829504
1403638628477829376
1403638628527829504
1403638628577829376
1403638628627829504
1403638628677829376
1403638628727829504
1403638628777829376
1403638628827829504
1403638628877829376
1403638628927829504
1403638628977829376
1403638629027829504
1403638629077829376
1403638629127829504
1403638629177829376
1403638629227829504
1403638629277829376
1403638629327829504
1403638629377829376
1403638629427829504
1403638629477829376
1403638629527829504
1403638629577829376
1403638629627829504
1403638629677829376
1403638629727829504
1403638629777829376
1403638629827829504
1403638629877829376
1403638629927829504
1403638629977829376
1403638630027829504
1403638630077829376
1403638630127829504
1403638630177829376
1403638630227829504
1403638630277829376
1403638630327829504
1403638630377829376
1403638630427829504
1403638630477829376
1403638630527829504
1403638630577829376
1403638630627829504
1403638630677829376
1403638630727829504
1403638630777829376
1403638630827829504
1403638630877829376
1403638630927829504
1403638630977829376
1403638631027829504
1403638631077829376
1403638631127829504
1403638631177829376
1403638631227829504
1403638631277829376
1403638631327829504
1403638631377829376
1403638631427829504
1403638631477829376
1403638631527829504
1403638631577829376
1403638631627829504
1403638631677829376
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/V101.txt
================================================
1403715273262142976
1403715273312143104
1403715273362142976
1403715273412143104
1403715273462142976
1403715273512143104
1403715273562142976
1403715273612143104
1403715273662142976
1403715273712143104
1403715273762142976
1403715273812143104
1403715273862142976
1403715273912143104
1403715273962142976
1403715274012143104
1403715274062142976
1403715274112143104
1403715274162142976
1403715274212143104
1403715274262142976
1403715274312143104
1403715274362142976
1403715274412143104
1403715274462142976
1403715274512143104
1403715274562142976
1403715274612143104
1403715274662142976
1403715274712143104
1403715274762142976
1403715274812143104
1403715274862142976
1403715274912143104
1403715274962142976
1403715275012143104
1403715275062142976
1403715275112143104
1403715275162142976
1403715275212143104
1403715275262142976
1403715275312143104
1403715275362142976
1403715275412143104
1403715275462142976
1403715275512143104
1403715275562142976
1403715275612143104
1403715275662142976
1403715275712143104
1403715275762142976
1403715275812143104
1403715275862142976
1403715275912143104
1403715275962142976
1403715276012143104
1403715276062142976
1403715276112143104
1403715276162142976
1403715276212143104
1403715276262142976
1403715276312143104
1403715276362142976
1403715276412143104
1403715276462142976
1403715276512143104
1403715276562142976
1403715276612143104
1403715276662142976
1403715276712143104
1403715276762142976
1403715276812143104
1403715276862142976
1403715276912143104
1403715276962142976
1403715277012143104
1403715277062142976
1403715277112143104
1403715277162142976
1403715277212143104
1403715277262142976
1403715277312143104
1403715277362142976
1403715277412143104
1403715277462142976
1403715277512143104
1403715277562142976
1403715277612143104
1403715277662142976
1403715277712143104
1403715277762142976
1403715277812143104
1403715277862142976
1403715277912143104
1403715277962142976
1403715278012143104
1403715278062142976
1403715278112143104
1403715278162142976
1403715278212143104
1403715278262142976
1403715278312143104
1403715278362142976
1403715278412143104
1403715278462142976
1403715278512143104
1403715278562142976
1403715278612143104
1403715278662142976
1403715278712143104
1403715278762142976
1403715278812143104
1403715278862142976
1403715278912143104
1403715278962142976
1403715279012143104
1403715279062142976
1403715279112143104
1403715279162142976
1403715279212143104
1403715279262142976
1403715279312143104
1403715279362142976
1403715279412143104
1403715279462142976
1403715279512143104
1403715279562142976
1403715279612143104
1403715279662142976
1403715279712143104
1403715279762142976
1403715279812143104
1403715279862142976
1403715279912143104
1403715279962142976
1403715280012143104
1403715280062142976
1403715280112143104
1403715280162142976
1403715280212143104
1403715280262142976
1403715280312143104
1403715280362142976
1403715280412143104
1403715280462142976
1403715280512143104
1403715280562142976
1403715280612143104
1403715280662142976
1403715280712143104
1403715280762142976
1403715280812143104
1403715280862142976
1403715280912143104
1403715280962142976
1403715281012143104
1403715281062142976
1403715281112143104
1403715281162142976
1403715281212143104
1403715281262142976
1403715281312143104
1403715281362142976
1403715281412143104
1403715281462142976
1403715281512143104
1403715281562142976
1403715281612143104
1403715281662142976
1403715281712143104
1403715281762142976
1403715281812143104
1403715281862142976
1403715281912143104
1403715281962142976
1403715282012143104
1403715282062142976
1403715282112143104
1403715282162142976
1403715282212143104
1403715282262142976
1403715282312143104
1403715282362142976
1403715282412143104
1403715282462142976
1403715282512143104
1403715282562142976
1403715282612143104
1403715282662142976
1403715282712143104
1403715282762142976
1403715282812143104
1403715282862142976
1403715282912143104
1403715282962142976
1403715283012143104
1403715283062142976
1403715283112143104
1403715283162142976
1403715283212143104
1403715283262142976
1403715283312143104
1403715283362142976
1403715283412143104
1403715283462142976
1403715283512143104
1403715283562142976
1403715283612143104
1403715283662142976
1403715283712143104
1403715283762142976
1403715283812143104
1403715283862142976
1403715283912143104
1403715283962142976
1403715284012143104
1403715284062142976
1403715284112143104
1403715284162142976
1403715284212143104
1403715284262142976
1403715284312143104
1403715284362142976
1403715284412143104
1403715284462142976
1403715284512143104
1403715284562142976
1403715284612143104
1403715284662142976
1403715284712143104
1403715284762142976
1403715284812143104
1403715284862142976
1403715284912143104
1403715284962142976
1403715285012143104
1403715285062142976
1403715285112143104
1403715285162142976
1403715285212143104
1403715285262142976
1403715285312143104
1403715285362142976
1403715285412143104
1403715285462142976
1403715285512143104
1403715285562142976
1403715285612143104
1403715285662142976
1403715285712143104
1403715285762142976
1403715285812143104
1403715285862142976
1403715285912143104
1403715285962142976
1403715286012143104
1403715286062142976
1403715286112143104
1403715286162142976
1403715286212143104
1403715286262142976
1403715286312143104
1403715286362142976
1403715286412143104
1403715286462142976
1403715286512143104
1403715286562142976
1403715286612143104
1403715286662142976
1403715286712143104
1403715286762142976
1403715286812143104
1403715286862142976
1403715286912143104
1403715286962142976
1403715287012143104
1403715287062142976
1403715287112143104
1403715287162142976
1403715287212143104
1403715287262142976
1403715287312143104
1403715287362142976
1403715287412143104
1403715287462142976
1403715287512143104
1403715287562142976
1403715287612143104
1403715287662142976
1403715287712143104
1403715287762142976
1403715287812143104
1403715287862142976
1403715287912143104
1403715287962142976
1403715288012143104
1403715288062142976
1403715288112143104
1403715288162142976
1403715288212143104
1403715288262142976
1403715288312143104
1403715288362142976
1403715288412143104
1403715288462142976
1403715288512143104
1403715288562142976
1403715288612143104
1403715288662142976
1403715288712143104
1403715288762142976
1403715288812143104
1403715288862142976
1403715288912143104
1403715288962142976
1403715289012143104
1403715289062142976
1403715289112143104
1403715289162142976
1403715289212143104
1403715289262142976
1403715289312143104
1403715289362142976
1403715289412143104
1403715289462142976
1403715289512143104
1403715289562142976
1403715289612143104
1403715289662142976
1403715289712143104
1403715289762142976
1403715289812143104
1403715289862142976
1403715289912143104
1403715289962142976
1403715290012143104
1403715290062142976
1403715290112143104
1403715290162142976
1403715290212143104
1403715290262142976
1403715290312143104
1403715290362142976
1403715290412143104
1403715290462142976
1403715290512143104
1403715290562142976
1403715290612143104
1403715290662142976
1403715290712143104
1403715290762142976
1403715290812143104
1403715290862142976
1403715290912143104
1403715290962142976
1403715291012143104
1403715291062142976
1403715291112143104
1403715291162142976
1403715291212143104
1403715291262142976
1403715291312143104
1403715291362142976
1403715291412143104
1403715291462142976
1403715291512143104
1403715291562142976
1403715291612143104
1403715291662142976
1403715291712143104
1403715291762142976
1403715291812143104
1403715291862142976
1403715291912143104
1403715291962142976
1403715292012143104
1403715292062142976
1403715292112143104
1403715292162142976
1403715292212143104
1403715292262142976
1403715292312143104
1403715292362142976
1403715292412143104
1403715292462142976
1403715292512143104
1403715292562142976
1403715292612143104
1403715292662142976
1403715292712143104
1403715292762142976
1403715292812143104
1403715292862142976
1403715292912143104
1403715292962142976
1403715293012143104
1403715293062142976
1403715293112143104
1403715293162142976
1403715293212143104
1403715293262142976
1403715293312143104
1403715293362142976
1403715293412143104
1403715293462142976
1403715293512143104
1403715293562142976
1403715293612143104
1403715293662142976
1403715293712143104
1403715293762142976
1403715293812143104
1403715293862142976
1403715293912143104
1403715293962142976
1403715294012143104
1403715294062142976
1403715294112143104
1403715294162142976
1403715294212143104
1403715294262142976
1403715294312143104
1403715294362142976
1403715294412143104
1403715294462142976
1403715294512143104
1403715294562142976
1403715294612143104
1403715294662142976
1403715294712143104
1403715294762142976
1403715294812143104
1403715294862142976
1403715294912143104
1403715294962142976
1403715295012143104
1403715295062142976
1403715295112143104
1403715295162142976
1403715295212143104
1403715295262142976
1403715295312143104
1403715295362142976
1403715295412143104
1403715295462142976
1403715295512143104
1403715295562142976
1403715295612143104
1403715295662142976
1403715295712143104
1403715295762142976
1403715295812143104
1403715295862142976
1403715295912143104
1403715295962142976
1403715296012143104
1403715296062142976
1403715296112143104
1403715296162142976
1403715296212143104
1403715296262142976
1403715296312143104
1403715296362142976
1403715296412143104
1403715296462142976
1403715296512143104
1403715296562142976
1403715296612143104
1403715296662142976
1403715296712143104
1403715296762142976
1403715296812143104
1403715296862142976
1403715296912143104
1403715296962142976
1403715297012143104
1403715297062142976
1403715297112143104
1403715297162142976
1403715297212143104
1403715297262142976
1403715297312143104
1403715297362142976
1403715297412143104
1403715297462142976
1403715297512143104
1403715297562142976
1403715297612143104
1403715297662142976
1403715297712143104
1403715297762142976
1403715297812143104
1403715297862142976
1403715297912143104
1403715297962142976
1403715298012143104
1403715298062142976
1403715298112143104
1403715298162142976
1403715298212143104
1403715298262142976
1403715298312143104
1403715298362142976
1403715298412143104
1403715298462142976
1403715298512143104
1403715298562142976
1403715298612143104
1403715298662142976
1403715298712143104
1403715298762142976
1403715298812143104
1403715298862142976
1403715298912143104
1403715298962142976
1403715299012143104
1403715299062142976
1403715299112143104
1403715299162142976
1403715299212143104
1403715299262142976
1403715299312143104
1403715299362142976
1403715299412143104
1403715299462142976
1403715299512143104
1403715299562142976
1403715299612143104
1403715299662142976
1403715299712143104
1403715299762142976
1403715299812143104
1403715299862142976
1403715299912143104
1403715299962142976
1403715300012143104
1403715300062142976
1403715300112143104
1403715300162142976
1403715300212143104
1403715300262142976
1403715300312143104
1403715300362142976
1403715300412143104
1403715300462142976
1403715300512143104
1403715300562142976
1403715300612143104
1403715300662142976
1403715300712143104
1403715300762142976
1403715300812143104
1403715300862142976
1403715300912143104
1403715300962142976
1403715301012143104
1403715301062142976
1403715301112143104
1403715301162142976
1403715301212143104
1403715301262142976
1403715301312143104
1403715301362142976
1403715301412143104
1403715301462142976
1403715301512143104
1403715301562142976
1403715301612143104
1403715301662142976
1403715301712143104
1403715301762142976
1403715301812143104
1403715301862142976
1403715301912143104
1403715301962142976
1403715302012143104
1403715302062142976
1403715302112143104
1403715302162142976
1403715302212143104
1403715302262142976
1403715302312143104
1403715302362142976
1403715302412143104
1403715302462142976
1403715302512143104
1403715302562142976
1403715302612143104
1403715302662142976
1403715302712143104
1403715302762142976
1403715302812143104
1403715302862142976
1403715302912143104
1403715302962142976
1403715303012143104
1403715303062142976
1403715303112143104
1403715303162142976
1403715303212143104
1403715303262142976
1403715303312143104
1403715303362142976
1403715303412143104
1403715303462142976
1403715303512143104
1403715303562142976
1403715303612143104
1403715303662142976
1403715303712143104
1403715303762142976
1403715303812143104
1403715303862142976
1403715303912143104
1403715303962142976
1403715304012143104
1403715304062142976
1403715304112143104
1403715304162142976
1403715304212143104
1403715304262142976
1403715304312143104
1403715304362142976
1403715304412143104
1403715304462142976
1403715304512143104
1403715304562142976
1403715304612143104
1403715304662142976
1403715304712143104
1403715304762142976
1403715304812143104
1403715304862142976
1403715304912143104
1403715304962142976
1403715305012143104
1403715305062142976
1403715305112143104
1403715305162142976
1403715305212143104
1403715305262142976
1403715305312143104
1403715305362142976
1403715305412143104
1403715305462142976
1403715305512143104
1403715305562142976
1403715305612143104
1403715305662142976
1403715305712143104
1403715305762142976
1403715305812143104
1403715305862142976
1403715305912143104
1403715305962142976
1403715306012143104
1403715306062142976
1403715306112143104
1403715306162142976
1403715306212143104
1403715306262142976
1403715306312143104
1403715306362142976
1403715306412143104
1403715306462142976
1403715306512143104
1403715306562142976
1403715306612143104
1403715306662142976
1403715306712143104
1403715306762142976
1403715306812143104
1403715306862142976
1403715306912143104
1403715306962142976
1403715307012143104
1403715307062142976
1403715307112143104
1403715307162142976
1403715307212143104
1403715307262142976
1403715307312143104
1403715307362142976
1403715307412143104
1403715307462142976
1403715307512143104
1403715307562142976
1403715307612143104
1403715307662142976
1403715307712143104
1403715307762142976
1403715307812143104
1403715307862142976
1403715307912143104
1403715307962142976
1403715308012143104
1403715308062142976
1403715308112143104
1403715308162142976
1403715308212143104
1403715308262142976
1403715308312143104
1403715308362142976
1403715308412143104
1403715308462142976
1403715308512143104
1403715308562142976
1403715308612143104
1403715308662142976
1403715308712143104
1403715308762142976
1403715308812143104
1403715308862142976
1403715308912143104
1403715308962142976
1403715309012143104
1403715309062142976
1403715309112143104
1403715309162142976
1403715309212143104
1403715309262142976
1403715309312143104
1403715309362142976
1403715309412143104
1403715309462142976
1403715309512143104
1403715309562142976
1403715309612143104
1403715309662142976
1403715309712143104
1403715309762142976
1403715309812143104
1403715309862142976
1403715309912143104
1403715309962142976
1403715310012143104
1403715310062142976
1403715310112143104
1403715310162142976
1403715310212143104
1403715310262142976
1403715310312143104
1403715310362142976
1403715310412143104
1403715310462142976
1403715310512143104
1403715310562142976
1403715310612143104
1403715310662142976
1403715310712143104
1403715310762142976
1403715310812143104
1403715310862142976
1403715310912143104
1403715310962142976
1403715311012143104
1403715311062142976
1403715311112143104
1403715311162142976
1403715311212143104
1403715311262142976
1403715311312143104
1403715311362142976
1403715311412143104
1403715311462142976
1403715311512143104
1403715311562142976
1403715311612143104
1403715311662142976
1403715311712143104
1403715311762142976
1403715311812143104
1403715311862142976
1403715311912143104
1403715311962142976
1403715312012143104
1403715312062142976
1403715312112143104
1403715312162142976
1403715312212143104
1403715312262142976
1403715312312143104
1403715312362142976
1403715312412143104
1403715312462142976
1403715312512143104
1403715312562142976
1403715312612143104
1403715312662142976
1403715312712143104
1403715312762142976
1403715312812143104
1403715312862142976
1403715312912143104
1403715312962142976
1403715313012143104
1403715313062142976
1403715313112143104
1403715313162142976
1403715313212143104
1403715313262142976
1403715313312143104
1403715313362142976
1403715313412143104
1403715313462142976
1403715313512143104
1403715313562142976
1403715313612143104
1403715313662142976
1403715313712143104
1403715313762142976
1403715313812143104
1403715313862142976
1403715313912143104
1403715313962142976
1403715314012143104
1403715314062142976
1403715314112143104
1403715314162142976
1403715314212143104
1403715314262142976
1403715314312143104
1403715314362142976
1403715314412143104
1403715314462142976
1403715314512143104
1403715314562142976
1403715314612143104
1403715314662142976
1403715314712143104
1403715314762142976
1403715314812143104
1403715314862142976
1403715314912143104
1403715314962142976
1403715315012143104
1403715315062142976
1403715315112143104
1403715315162142976
1403715315212143104
1403715315262142976
1403715315312143104
1403715315362142976
1403715315412143104
1403715315462142976
1403715315512143104
1403715315562142976
1403715315612143104
1403715315662142976
1403715315712143104
1403715315762142976
1403715315812143104
1403715315862142976
1403715315912143104
1403715315962142976
1403715316012143104
1403715316062142976
1403715316112143104
1403715316162142976
1403715316212143104
1403715316262142976
1403715316312143104
1403715316362142976
1403715316412143104
1403715316462142976
1403715316512143104
1403715316562142976
1403715316612143104
1403715316662142976
1403715316712143104
1403715316762142976
1403715316812143104
1403715316862142976
1403715316912143104
1403715316962142976
1403715317012143104
1403715317062142976
1403715317112143104
1403715317162142976
1403715317212143104
1403715317262142976
1403715317312143104
1403715317362142976
1403715317412143104
1403715317462142976
1403715317512143104
1403715317562142976
1403715317612143104
1403715317662142976
1403715317712143104
1403715317762142976
1403715317812143104
1403715317862142976
1403715317912143104
1403715317962142976
1403715318012143104
1403715318062142976
1403715318112143104
1403715318162142976
1403715318212143104
1403715318262142976
1403715318312143104
1403715318362142976
1403715318412143104
1403715318462142976
1403715318512143104
1403715318562142976
1403715318612143104
1403715318662142976
1403715318712143104
1403715318762142976
1403715318812143104
1403715318862142976
1403715318912143104
1403715318962142976
1403715319012143104
1403715319062142976
1403715319112143104
1403715319162142976
1403715319212143104
1403715319262142976
1403715319312143104
1403715319362142976
1403715319412143104
1403715319462142976
1403715319512143104
1403715319562142976
1403715319612143104
1403715319662142976
1403715319712143104
1403715319762142976
1403715319812143104
1403715319862142976
1403715319912143104
1403715319962142976
1403715320012143104
1403715320062142976
1403715320112143104
1403715320162142976
1403715320212143104
1403715320262142976
1403715320312143104
1403715320362142976
1403715320412143104
1403715320462142976
1403715320512143104
1403715320562142976
1403715320612143104
1403715320662142976
1403715320712143104
1403715320762142976
1403715320812143104
1403715320862142976
1403715320912143104
1403715320962142976
1403715321012143104
1403715321062142976
1403715321112143104
1403715321162142976
1403715321212143104
1403715321262142976
1403715321312143104
1403715321362142976
1403715321412143104
1403715321462142976
1403715321512143104
1403715321562142976
1403715321612143104
1403715321662142976
1403715321712143104
1403715321762142976
1403715321812143104
1403715321862142976
1403715321912143104
1403715321962142976
1403715322012143104
1403715322062142976
1403715322112143104
1403715322162142976
1403715322212143104
1403715322262142976
1403715322312143104
1403715322362142976
1403715322412143104
1403715322462142976
1403715322512143104
1403715322562142976
1403715322612143104
1403715322662142976
1403715322712143104
1403715322762142976
1403715322812143104
1403715322862142976
1403715322912143104
1403715322962142976
1403715323012143104
1403715323062142976
1403715323112143104
1403715323162142976
1403715323212143104
1403715323262142976
1403715323312143104
1403715323362142976
1403715323412143104
1403715323462142976
1403715323512143104
1403715323562142976
1403715323612143104
1403715323662142976
1403715323712143104
1403715323762142976
1403715323812143104
1403715323862142976
1403715323912143104
1403715323962142976
1403715324012143104
1403715324062142976
1403715324112143104
1403715324162142976
1403715324212143104
1403715324262142976
1403715324312143104
1403715324362142976
1403715324412143104
1403715324462142976
1403715324512143104
1403715324562142976
1403715324612143104
1403715324662142976
1403715324712143104
1403715324762142976
1403715324812143104
1403715324862142976
1403715324912143104
1403715324962142976
1403715325012143104
1403715325062142976
1403715325112143104
1403715325162142976
1403715325212143104
1403715325262142976
1403715325312143104
1403715325362142976
1403715325412143104
1403715325462142976
1403715325512143104
1403715325562142976
1403715325612143104
1403715325662142976
1403715325712143104
1403715325762142976
1403715325812143104
1403715325862142976
1403715325912143104
1403715325962142976
1403715326012143104
1403715326062142976
1403715326112143104
1403715326162142976
1403715326212143104
1403715326262142976
1403715326312143104
1403715326362142976
1403715326412143104
1403715326462142976
1403715326512143104
1403715326562142976
1403715326612143104
1403715326662142976
1403715326712143104
1403715326762142976
1403715326812143104
1403715326862142976
1403715326912143104
1403715326962142976
1403715327012143104
1403715327062142976
1403715327112143104
1403715327162142976
1403715327212143104
1403715327262142976
1403715327312143104
1403715327362142976
1403715327412143104
1403715327462142976
1403715327512143104
1403715327562142976
1403715327612143104
1403715327662142976
1403715327712143104
1403715327762142976
1403715327812143104
1403715327862142976
1403715327912143104
1403715327962142976
1403715328012143104
1403715328062142976
1403715328112143104
1403715328162142976
1403715328212143104
1403715328262142976
1403715328312143104
1403715328362142976
1403715328412143104
1403715328462142976
1403715328512143104
1403715328562142976
1403715328612143104
1403715328662142976
1403715328712143104
1403715328762142976
1403715328812143104
1403715328862142976
1403715328912143104
1403715328962142976
1403715329012143104
1403715329062142976
1403715329112143104
1403715329162142976
1403715329212143104
1403715329262142976
1403715329312143104
1403715329362142976
1403715329412143104
1403715329462142976
1403715329512143104
1403715329562142976
1403715329612143104
1403715329662142976
1403715329712143104
1403715329762142976
1403715329812143104
1403715329862142976
1403715329912143104
1403715329962142976
1403715330012143104
1403715330062142976
1403715330112143104
1403715330162142976
1403715330212143104
1403715330262142976
1403715330312143104
1403715330362142976
1403715330412143104
1403715330462142976
1403715330512143104
1403715330562142976
1403715330612143104
1403715330662142976
1403715330712143104
1403715330762142976
1403715330812143104
1403715330862142976
1403715330912143104
1403715330962142976
1403715331012143104
1403715331062142976
1403715331112143104
1403715331162142976
1403715331212143104
1403715331262142976
1403715331312143104
1403715331362142976
1403715331412143104
1403715331462142976
1403715331512143104
1403715331562142976
1403715331612143104
1403715331662142976
1403715331712143104
1403715331762142976
1403715331812143104
1403715331862142976
1403715331912143104
1403715331962142976
1403715332012143104
1403715332062142976
1403715332112143104
1403715332162142976
1403715332212143104
1403715332262142976
1403715332312143104
1403715332362142976
1403715332412143104
1403715332462142976
1403715332512143104
1403715332562142976
1403715332612143104
1403715332662142976
1403715332712143104
1403715332762142976
1403715332812143104
1403715332862142976
1403715332912143104
1403715332962142976
1403715333012143104
1403715333062142976
1403715333112143104
1403715333162142976
1403715333212143104
1403715333262142976
1403715333312143104
1403715333362142976
1403715333412143104
1403715333462142976
1403715333512143104
1403715333562142976
1403715333612143104
1403715333662142976
1403715333712143104
1403715333762142976
1403715333812143104
1403715333862142976
1403715333912143104
1403715333962142976
1403715334012143104
1403715334062142976
1403715334112143104
1403715334162142976
1403715334212143104
1403715334262142976
1403715334312143104
1403715334362142976
1403715334412143104
1403715334462142976
1403715334512143104
1403715334562142976
1403715334612143104
1403715334662142976
1403715334712143104
1403715334762142976
1403715334812143104
1403715334862142976
1403715334912143104
1403715334962142976
1403715335012143104
1403715335062142976
1403715335112143104
1403715335162142976
1403715335212143104
1403715335262142976
1403715335312143104
1403715335362142976
1403715335412143104
1403715335462142976
1403715335512143104
1403715335562142976
1403715335612143104
1403715335662142976
1403715335712143104
1403715335762142976
1403715335812143104
1403715335862142976
1403715335912143104
1403715335962142976
1403715336012143104
1403715336062142976
1403715336112143104
1403715336162142976
1403715336212143104
1403715336262142976
1403715336312143104
1403715336362142976
1403715336412143104
1403715336462142976
1403715336512143104
1403715336562142976
1403715336612143104
1403715336662142976
1403715336712143104
1403715336762142976
1403715336812143104
1403715336862142976
1403715336912143104
1403715336962142976
1403715337012143104
1403715337062142976
1403715337112143104
1403715337162142976
1403715337212143104
1403715337262142976
1403715337312143104
1403715337362142976
1403715337412143104
1403715337462142976
1403715337512143104
1403715337562142976
1403715337612143104
1403715337662142976
1403715337712143104
1403715337762142976
1403715337812143104
1403715337862142976
1403715337912143104
1403715337962142976
1403715338012143104
1403715338062142976
1403715338112143104
1403715338162142976
1403715338212143104
1403715338262142976
1403715338312143104
1403715338362142976
1403715338412143104
1403715338462142976
1403715338512143104
1403715338562142976
1403715338612143104
1403715338662142976
1403715338712143104
1403715338762142976
1403715338812143104
1403715338862142976
1403715338912143104
1403715338962142976
1403715339012143104
1403715339062142976
1403715339112143104
1403715339162142976
1403715339212143104
1403715339262142976
1403715339312143104
1403715339362142976
1403715339412143104
1403715339462142976
1403715339512143104
1403715339562142976
1403715339612143104
1403715339662142976
1403715339712143104
1403715339762142976
1403715339812143104
1403715339862142976
1403715339912143104
1403715339962142976
1403715340012143104
1403715340062142976
1403715340112143104
1403715340162142976
1403715340212143104
1403715340262142976
1403715340312143104
1403715340362142976
1403715340412143104
1403715340462142976
1403715340512143104
1403715340562142976
1403715340612143104
1403715340662142976
1403715340712143104
1403715340762142976
1403715340812143104
1403715340862142976
1403715340912143104
1403715340962142976
1403715341012143104
1403715341062142976
1403715341112143104
1403715341162142976
1403715341212143104
1403715341262142976
1403715341312143104
1403715341362142976
1403715341412143104
1403715341462142976
1403715341512143104
1403715341562142976
1403715341612143104
1403715341662142976
1403715341712143104
1403715341762142976
1403715341812143104
1403715341862142976
1403715341912143104
1403715341962142976
1403715342012143104
1403715342062142976
1403715342112143104
1403715342162142976
1403715342212143104
1403715342262142976
1403715342312143104
1403715342362142976
1403715342412143104
1403715342462142976
1403715342512143104
1403715342562142976
1403715342612143104
1403715342662142976
1403715342712143104
1403715342762142976
1403715342812143104
1403715342862142976
1403715342912143104
1403715342962142976
1403715343012143104
1403715343062142976
1403715343112143104
1403715343162142976
1403715343212143104
1403715343262142976
1403715343312143104
1403715343362142976
1403715343412143104
1403715343462142976
1403715343512143104
1403715343562142976
1403715343612143104
1403715343662142976
1403715343712143104
1403715343762142976
1403715343812143104
1403715343862142976
1403715343912143104
1403715343962142976
1403715344012143104
1403715344062142976
1403715344112143104
1403715344162142976
1403715344212143104
1403715344262142976
1403715344312143104
1403715344362142976
1403715344412143104
1403715344462142976
1403715344512143104
1403715344562142976
1403715344612143104
1403715344662142976
1403715344712143104
1403715344762142976
1403715344812143104
1403715344862142976
1403715344912143104
1403715344962142976
1403715345012143104
1403715345062142976
1403715345112143104
1403715345162142976
1403715345212143104
1403715345262142976
1403715345312143104
1403715345362142976
1403715345412143104
1403715345462142976
1403715345512143104
1403715345562142976
1403715345612143104
1403715345662142976
1403715345712143104
1403715345762142976
1403715345812143104
1403715345862142976
1403715345912143104
1403715345962142976
1403715346012143104
1403715346062142976
1403715346112143104
1403715346162142976
1403715346212143104
1403715346262142976
1403715346312143104
1403715346362142976
1403715346412143104
1403715346462142976
1403715346512143104
1403715346562142976
1403715346612143104
1403715346662142976
1403715346712143104
1403715346762142976
1403715346812143104
1403715346862142976
1403715346912143104
1403715346962142976
1403715347012143104
1403715347062142976
1403715347112143104
1403715347162142976
1403715347212143104
1403715347262142976
1403715347312143104
1403715347362142976
1403715347412143104
1403715347462142976
1403715347512143104
1403715347562142976
1403715347612143104
1403715347662142976
1403715347712143104
1403715347762142976
1403715347812143104
1403715347862142976
1403715347912143104
1403715347962142976
1403715348012143104
1403715348062142976
1403715348112143104
1403715348162142976
1403715348212143104
1403715348262142976
1403715348312143104
1403715348362142976
1403715348412143104
1403715348462142976
1403715348512143104
1403715348562142976
1403715348612143104
1403715348662142976
1403715348712143104
1403715348762142976
1403715348812143104
1403715348862142976
1403715348912143104
1403715348962142976
1403715349012143104
1403715349062142976
1403715349112143104
1403715349162142976
1403715349212143104
1403715349262142976
1403715349312143104
1403715349362142976
1403715349412143104
1403715349462142976
1403715349512143104
1403715349562142976
1403715349612143104
1403715349662142976
1403715349712143104
1403715349762142976
1403715349812143104
1403715349862142976
1403715349912143104
1403715349962142976
1403715350012143104
1403715350062142976
1403715350112143104
1403715350162142976
1403715350212143104
1403715350262142976
1403715350312143104
1403715350362142976
1403715350412143104
1403715350462142976
1403715350512143104
1403715350562142976
1403715350612143104
1403715350662142976
1403715350712143104
1403715350762142976
1403715350812143104
1403715350862142976
1403715350912143104
1403715350962142976
1403715351012143104
1403715351062142976
1403715351112143104
1403715351162142976
1403715351212143104
1403715351262142976
1403715351312143104
1403715351362142976
1403715351412143104
1403715351462142976
1403715351512143104
1403715351562142976
1403715351612143104
1403715351662142976
1403715351712143104
1403715351762142976
1403715351812143104
1403715351862142976
1403715351912143104
1403715351962142976
1403715352012143104
1403715352062142976
1403715352112143104
1403715352162142976
1403715352212143104
1403715352262142976
1403715352312143104
1403715352362142976
1403715352412143104
1403715352462142976
1403715352512143104
1403715352562142976
1403715352612143104
1403715352662142976
1403715352712143104
1403715352762142976
1403715352812143104
1403715352862142976
1403715352912143104
1403715352962142976
1403715353012143104
1403715353062142976
1403715353112143104
1403715353162142976
1403715353212143104
1403715353262142976
1403715353312143104
1403715353362142976
1403715353412143104
1403715353462142976
1403715353512143104
1403715353562142976
1403715353612143104
1403715353662142976
1403715353712143104
1403715353762142976
1403715353812143104
1403715353862142976
1403715353912143104
1403715353962142976
1403715354012143104
1403715354062142976
1403715354112143104
1403715354162142976
1403715354212143104
1403715354262142976
1403715354312143104
1403715354362142976
1403715354412143104
1403715354462142976
1403715354512143104
1403715354562142976
1403715354612143104
1403715354662142976
1403715354712143104
1403715354762142976
1403715354812143104
1403715354862142976
1403715354912143104
1403715354962142976
1403715355012143104
1403715355062142976
1403715355112143104
1403715355162142976
1403715355212143104
1403715355262142976
1403715355312143104
1403715355362142976
1403715355412143104
1403715355462142976
1403715355512143104
1403715355562142976
1403715355612143104
1403715355662142976
1403715355712143104
1403715355762142976
1403715355812143104
1403715355862142976
1403715355912143104
1403715355962142976
1403715356012143104
1403715356062142976
1403715356112143104
1403715356162142976
1403715356212143104
1403715356262142976
1403715356312143104
1403715356362142976
1403715356412143104
1403715356462142976
1403715356512143104
1403715356562142976
1403715356612143104
1403715356662142976
1403715356712143104
1403715356762142976
1403715356812143104
1403715356862142976
1403715356912143104
1403715356962142976
1403715357012143104
1403715357062142976
1403715357112143104
1403715357162142976
1403715357212143104
1403715357262142976
1403715357312143104
1403715357362142976
1403715357412143104
1403715357462142976
1403715357512143104
1403715357562142976
1403715357612143104
1403715357662142976
1403715357712143104
1403715357762142976
1403715357812143104
1403715357862142976
1403715357912143104
1403715357962142976
1403715358012143104
1403715358062142976
1403715358112143104
1403715358162142976
1403715358212143104
1403715358262142976
1403715358312143104
1403715358362142976
1403715358412143104
1403715358462142976
1403715358512143104
1403715358562142976
1403715358612143104
1403715358662142976
1403715358712143104
1403715358762142976
1403715358812143104
1403715358862142976
1403715358912143104
1403715358962142976
1403715359012143104
1403715359062142976
1403715359112143104
1403715359162142976
1403715359212143104
1403715359262142976
1403715359312143104
1403715359362142976
1403715359412143104
1403715359462142976
1403715359512143104
1403715359562142976
1403715359612143104
1403715359662142976
1403715359712143104
1403715359762142976
1403715359812143104
1403715359862142976
1403715359912143104
1403715359962142976
1403715360012143104
1403715360062142976
1403715360112143104
1403715360162142976
1403715360212143104
1403715360262142976
1403715360312143104
1403715360362142976
1403715360412143104
1403715360462142976
1403715360512143104
1403715360562142976
1403715360612143104
1403715360662142976
1403715360712143104
1403715360762142976
1403715360812143104
1403715360862142976
1403715360912143104
1403715360962142976
1403715361012143104
1403715361062142976
1403715361112143104
1403715361162142976
1403715361212143104
1403715361262142976
1403715361312143104
1403715361362142976
1403715361412143104
1403715361462142976
1403715361512143104
1403715361562142976
1403715361612143104
1403715361662142976
1403715361712143104
1403715361762142976
1403715361812143104
1403715361862142976
1403715361912143104
1403715361962142976
1403715362012143104
1403715362062142976
1403715362112143104
1403715362162142976
1403715362212143104
1403715362262142976
1403715362312143104
1403715362362142976
1403715362412143104
1403715362462142976
1403715362512143104
1403715362562142976
1403715362612143104
1403715362662142976
1403715362712143104
1403715362762142976
1403715362812143104
1403715362862142976
1403715362912143104
1403715362962142976
1403715363012143104
1403715363062142976
1403715363112143104
1403715363162142976
1403715363212143104
1403715363262142976
1403715363312143104
1403715363362142976
1403715363412143104
1403715363462142976
1403715363512143104
1403715363562142976
1403715363612143104
1403715363662142976
1403715363712143104
1403715363762142976
1403715363812143104
1403715363862142976
1403715363912143104
1403715363962142976
1403715364012143104
1403715364062142976
1403715364112143104
1403715364162142976
1403715364212143104
1403715364262142976
1403715364312143104
1403715364362142976
1403715364412143104
1403715364462142976
1403715364512143104
1403715364562142976
1403715364612143104
1403715364662142976
1403715364712143104
1403715364762142976
1403715364812143104
1403715364862142976
1403715364912143104
1403715364962142976
1403715365012143104
1403715365062142976
1403715365112143104
1403715365162142976
1403715365212143104
1403715365262142976
1403715365312143104
1403715365362142976
1403715365412143104
1403715365462142976
1403715365512143104
1403715365562142976
1403715365612143104
1403715365662142976
1403715365712143104
1403715365762142976
1403715365812143104
1403715365862142976
1403715365912143104
1403715365962142976
1403715366012143104
1403715366062142976
1403715366112143104
1403715366162142976
1403715366212143104
1403715366262142976
1403715366312143104
1403715366362142976
1403715366412143104
1403715366462142976
1403715366512143104
1403715366562142976
1403715366612143104
1403715366662142976
1403715366712143104
1403715366762142976
1403715366812143104
1403715366862142976
1403715366912143104
1403715366962142976
1403715367012143104
1403715367062142976
1403715367112143104
1403715367162142976
1403715367212143104
1403715367262142976
1403715367312143104
1403715367362142976
1403715367412143104
1403715367462142976
1403715367512143104
1403715367562142976
1403715367612143104
1403715367662142976
1403715367712143104
1403715367762142976
1403715367812143104
1403715367862142976
1403715367912143104
1403715367962142976
1403715368012143104
1403715368062142976
1403715368112143104
1403715368162142976
1403715368212143104
1403715368262142976
1403715368312143104
1403715368362142976
1403715368412143104
1403715368462142976
1403715368512143104
1403715368562142976
1403715368612143104
1403715368662142976
1403715368712143104
1403715368762142976
1403715368812143104
1403715368862142976
1403715368912143104
1403715368962142976
1403715369012143104
1403715369062142976
1403715369112143104
1403715369162142976
1403715369212143104
1403715369262142976
1403715369312143104
1403715369362142976
1403715369412143104
1403715369462142976
1403715369512143104
1403715369562142976
1403715369612143104
1403715369662142976
1403715369712143104
1403715369762142976
1403715369812143104
1403715369862142976
1403715369912143104
1403715369962142976
1403715370012143104
1403715370062142976
1403715370112143104
1403715370162142976
1403715370212143104
1403715370262142976
1403715370312143104
1403715370362142976
1403715370412143104
1403715370462142976
1403715370512143104
1403715370562142976
1403715370612143104
1403715370662142976
1403715370712143104
1403715370762142976
1403715370812143104
1403715370862142976
1403715370912143104
1403715370962142976
1403715371012143104
1403715371062142976
1403715371112143104
1403715371162142976
1403715371212143104
1403715371262142976
1403715371312143104
1403715371362142976
1403715371412143104
1403715371462142976
1403715371512143104
1403715371562142976
1403715371612143104
1403715371662142976
1403715371712143104
1403715371762142976
1403715371812143104
1403715371862142976
1403715371912143104
1403715371962142976
1403715372012143104
1403715372062142976
1403715372112143104
1403715372162142976
1403715372212143104
1403715372262142976
1403715372312143104
1403715372362142976
1403715372412143104
1403715372462142976
1403715372512143104
1403715372562142976
1403715372612143104
1403715372662142976
1403715372712143104
1403715372762142976
1403715372812143104
1403715372862142976
1403715372912143104
1403715372962142976
1403715373012143104
1403715373062142976
1403715373112143104
1403715373162142976
1403715373212143104
1403715373262142976
1403715373312143104
1403715373362142976
1403715373412143104
1403715373462142976
1403715373512143104
1403715373562142976
1403715373612143104
1403715373662142976
1403715373712143104
1403715373762142976
1403715373812143104
1403715373862142976
1403715373912143104
1403715373962142976
1403715374012143104
1403715374062142976
1403715374112143104
1403715374162142976
1403715374212143104
1403715374262142976
1403715374312143104
1403715374362142976
1403715374412143104
1403715374462142976
1403715374512143104
1403715374562142976
1403715374612143104
1403715374662142976
1403715374712143104
1403715374762142976
1403715374812143104
1403715374862142976
1403715374912143104
1403715374962142976
1403715375012143104
1403715375062142976
1403715375112143104
1403715375162142976
1403715375212143104
1403715375262142976
1403715375312143104
1403715375362142976
1403715375412143104
1403715375462142976
1403715375512143104
1403715375562142976
1403715375612143104
1403715375662142976
1403715375712143104
1403715375762142976
1403715375812143104
1403715375862142976
1403715375912143104
1403715375962142976
1403715376012143104
1403715376062142976
1403715376112143104
1403715376162142976
1403715376212143104
1403715376262142976
1403715376312143104
1403715376362142976
1403715376412143104
1403715376462142976
1403715376512143104
1403715376562142976
1403715376612143104
1403715376662142976
1403715376712143104
1403715376762142976
1403715376812143104
1403715376862142976
1403715376912143104
1403715376962142976
1403715377012143104
1403715377062142976
1403715377112143104
1403715377162142976
1403715377212143104
1403715377262142976
1403715377312143104
1403715377362142976
1403715377412143104
1403715377462142976
1403715377512143104
1403715377562142976
1403715377612143104
1403715377662142976
1403715377712143104
1403715377762142976
1403715377812143104
1403715377862142976
1403715377912143104
1403715377962142976
1403715378012143104
1403715378062142976
1403715378112143104
1403715378162142976
1403715378212143104
1403715378262142976
1403715378312143104
1403715378362142976
1403715378412143104
1403715378462142976
1403715378512143104
1403715378562142976
1403715378612143104
1403715378662142976
1403715378712143104
1403715378762142976
1403715378812143104
1403715378862142976
1403715378912143104
1403715378962142976
1403715379012143104
1403715379062142976
1403715379112143104
1403715379162142976
1403715379212143104
1403715379262142976
1403715379312143104
1403715379362142976
1403715379412143104
1403715379462142976
1403715379512143104
1403715379562142976
1403715379612143104
1403715379662142976
1403715379712143104
1403715379762142976
1403715379812143104
1403715379862142976
1403715379912143104
1403715379962142976
1403715380012143104
1403715380062142976
1403715380112143104
1403715380162142976
1403715380212143104
1403715380262142976
1403715380312143104
1403715380362142976
1403715380412143104
1403715380462142976
1403715380512143104
1403715380562142976
1403715380612143104
1403715380662142976
1403715380712143104
1403715380762142976
1403715380812143104
1403715380862142976
1403715380912143104
1403715380962142976
1403715381012143104
1403715381062142976
1403715381112143104
1403715381162142976
1403715381212143104
1403715381262142976
1403715381312143104
1403715381362142976
1403715381412143104
1403715381462142976
1403715381512143104
1403715381562142976
1403715381612143104
1403715381662142976
1403715381712143104
1403715381762142976
1403715381812143104
1403715381862142976
1403715381912143104
1403715381962142976
1403715382012143104
1403715382062142976
1403715382112143104
1403715382162142976
1403715382212143104
1403715382262142976
1403715382312143104
1403715382362142976
1403715382412143104
1403715382462142976
1403715382512143104
1403715382562142976
1403715382612143104
1403715382662142976
1403715382712143104
1403715382762142976
1403715382812143104
1403715382862142976
1403715382912143104
1403715382962142976
1403715383012143104
1403715383062142976
1403715383112143104
1403715383162142976
1403715383212143104
1403715383262142976
1403715383312143104
1403715383362142976
1403715383412143104
1403715383462142976
1403715383512143104
1403715383562142976
1403715383612143104
1403715383662142976
1403715383712143104
1403715383762142976
1403715383812143104
1403715383862142976
1403715383912143104
1403715383962142976
1403715384012143104
1403715384062142976
1403715384112143104
1403715384162142976
1403715384212143104
1403715384262142976
1403715384312143104
1403715384362142976
1403715384412143104
1403715384462142976
1403715384512143104
1403715384562142976
1403715384612143104
1403715384662142976
1403715384712143104
1403715384762142976
1403715384812143104
1403715384862142976
1403715384912143104
1403715384962142976
1403715385012143104
1403715385062142976
1403715385112143104
1403715385162142976
1403715385212143104
1403715385262142976
1403715385312143104
1403715385362142976
1403715385412143104
1403715385462142976
1403715385512143104
1403715385562142976
1403715385612143104
1403715385662142976
1403715385712143104
1403715385762142976
1403715385812143104
1403715385862142976
1403715385912143104
1403715385962142976
1403715386012143104
1403715386062142976
1403715386112143104
1403715386162142976
1403715386212143104
1403715386262142976
1403715386312143104
1403715386362142976
1403715386412143104
1403715386462142976
1403715386512143104
1403715386562142976
1403715386612143104
1403715386662142976
1403715386712143104
1403715386762142976
1403715386812143104
1403715386862142976
1403715386912143104
1403715386962142976
1403715387012143104
1403715387062142976
1403715387112143104
1403715387162142976
1403715387212143104
1403715387262142976
1403715387312143104
1403715387362142976
1403715387412143104
1403715387462142976
1403715387512143104
1403715387562142976
1403715387612143104
1403715387662142976
1403715387712143104
1403715387762142976
1403715387812143104
1403715387862142976
1403715387912143104
1403715387962142976
1403715388012143104
1403715388062142976
1403715388112143104
1403715388162142976
1403715388212143104
1403715388262142976
1403715388312143104
1403715388362142976
1403715388412143104
1403715388462142976
1403715388512143104
1403715388562142976
1403715388612143104
1403715388662142976
1403715388712143104
1403715388762142976
1403715388812143104
1403715388862142976
1403715388912143104
1403715388962142976
1403715389012143104
1403715389062142976
1403715389112143104
1403715389162142976
1403715389212143104
1403715389262142976
1403715389312143104
1403715389362142976
1403715389412143104
1403715389462142976
1403715389512143104
1403715389562142976
1403715389612143104
1403715389662142976
1403715389712143104
1403715389762142976
1403715389812143104
1403715389862142976
1403715389912143104
1403715389962142976
1403715390012143104
1403715390062142976
1403715390112143104
1403715390162142976
1403715390212143104
1403715390262142976
1403715390312143104
1403715390362142976
1403715390412143104
1403715390462142976
1403715390512143104
1403715390562142976
1403715390612143104
1403715390662142976
1403715390712143104
1403715390762142976
1403715390812143104
1403715390862142976
1403715390912143104
1403715390962142976
1403715391012143104
1403715391062142976
1403715391112143104
1403715391162142976
1403715391212143104
1403715391262142976
1403715391312143104
1403715391362142976
1403715391412143104
1403715391462142976
1403715391512143104
1403715391562142976
1403715391612143104
1403715391662142976
1403715391712143104
1403715391762142976
1403715391812143104
1403715391862142976
1403715391912143104
1403715391962142976
1403715392012143104
1403715392062142976
1403715392112143104
1403715392162142976
1403715392212143104
1403715392262142976
1403715392312143104
1403715392362142976
1403715392412143104
1403715392462142976
1403715392512143104
1403715392562142976
1403715392612143104
1403715392662142976
1403715392712143104
1403715392762142976
1403715392812143104
1403715392862142976
1403715392912143104
1403715392962142976
1403715393012143104
1403715393062142976
1403715393112143104
1403715393162142976
1403715393212143104
1403715393262142976
1403715393312143104
1403715393362142976
1403715393412143104
1403715393462142976
1403715393512143104
1403715393562142976
1403715393612143104
1403715393662142976
1403715393712143104
1403715393762142976
1403715393812143104
1403715393862142976
1403715393912143104
1403715393962142976
1403715394012143104
1403715394062142976
1403715394112143104
1403715394162142976
1403715394212143104
1403715394262142976
1403715394312143104
1403715394362142976
1403715394412143104
1403715394462142976
1403715394512143104
1403715394562142976
1403715394612143104
1403715394662142976
1403715394712143104
1403715394762142976
1403715394812143104
1403715394862142976
1403715394912143104
1403715394962142976
1403715395012143104
1403715395062142976
1403715395112143104
1403715395162142976
1403715395212143104
1403715395262142976
1403715395312143104
1403715395362142976
1403715395412143104
1403715395462142976
1403715395512143104
1403715395562142976
1403715395612143104
1403715395662142976
1403715395712143104
1403715395762142976
1403715395812143104
1403715395862142976
1403715395912143104
1403715395962142976
1403715396012143104
1403715396062142976
1403715396112143104
1403715396162142976
1403715396212143104
1403715396262142976
1403715396312143104
1403715396362142976
1403715396412143104
1403715396462142976
1403715396512143104
1403715396562142976
1403715396612143104
1403715396662142976
1403715396712143104
1403715396762142976
1403715396812143104
1403715396862142976
1403715396912143104
1403715396962142976
1403715397012143104
1403715397062142976
1403715397112143104
1403715397162142976
1403715397212143104
1403715397262142976
1403715397312143104
1403715397362142976
1403715397412143104
1403715397462142976
1403715397512143104
1403715397562142976
1403715397612143104
1403715397662142976
1403715397712143104
1403715397762142976
1403715397812143104
1403715397862142976
1403715397912143104
1403715397962142976
1403715398012143104
1403715398062142976
1403715398112143104
1403715398162142976
1403715398212143104
1403715398262142976
1403715398312143104
1403715398362142976
1403715398412143104
1403715398462142976
1403715398512143104
1403715398562142976
1403715398612143104
1403715398662142976
1403715398712143104
1403715398762142976
1403715398812143104
1403715398862142976
1403715398912143104
1403715398962142976
1403715399012143104
1403715399062142976
1403715399112143104
1403715399162142976
1403715399212143104
1403715399262142976
1403715399312143104
1403715399362142976
1403715399412143104
1403715399462142976
1403715399512143104
1403715399562142976
1403715399612143104
1403715399662142976
1403715399712143104
1403715399762142976
1403715399812143104
1403715399862142976
1403715399912143104
1403715399962142976
1403715400012143104
1403715400062142976
1403715400112143104
1403715400162142976
1403715400212143104
1403715400262142976
1403715400312143104
1403715400362142976
1403715400412143104
1403715400462142976
1403715400512143104
1403715400562142976
1403715400612143104
1403715400662142976
1403715400712143104
1403715400762142976
1403715400812143104
1403715400862142976
1403715400912143104
1403715400962142976
1403715401012143104
1403715401062142976
1403715401112143104
1403715401162142976
1403715401212143104
1403715401262142976
1403715401312143104
1403715401362142976
1403715401412143104
1403715401462142976
1403715401512143104
1403715401562142976
1403715401612143104
1403715401662142976
1403715401712143104
1403715401762142976
1403715401812143104
1403715401862142976
1403715401912143104
1403715401962142976
1403715402012143104
1403715402062142976
1403715402112143104
1403715402162142976
1403715402212143104
1403715402262142976
1403715402312143104
1403715402362142976
1403715402412143104
1403715402462142976
1403715402512143104
1403715402562142976
1403715402612143104
1403715402662142976
1403715402712143104
1403715402762142976
1403715402812143104
1403715402862142976
1403715402912143104
1403715402962142976
1403715403012143104
1403715403062142976
1403715403112143104
1403715403162142976
1403715403212143104
1403715403262142976
1403715403312143104
1403715403362142976
1403715403412143104
1403715403462142976
1403715403512143104
1403715403562142976
1403715403612143104
1403715403662142976
1403715403712143104
1403715403762142976
1403715403812143104
1403715403862142976
1403715403912143104
1403715403962142976
1403715404012143104
1403715404062142976
1403715404112143104
1403715404162142976
1403715404212143104
1403715404262142976
1403715404312143104
1403715404362142976
1403715404412143104
1403715404462142976
1403715404512143104
1403715404562142976
1403715404612143104
1403715404662142976
1403715404712143104
1403715404762142976
1403715404812143104
1403715404862142976
1403715404912143104
1403715404962142976
1403715405012143104
1403715405062142976
1403715405112143104
1403715405162142976
1403715405212143104
1403715405262142976
1403715405312143104
1403715405362142976
1403715405412143104
1403715405462142976
1403715405512143104
1403715405562142976
1403715405612143104
1403715405662142976
1403715405712143104
1403715405762142976
1403715405812143104
1403715405862142976
1403715405912143104
1403715405962142976
1403715406012143104
1403715406062142976
1403715406112143104
1403715406162142976
1403715406212143104
1403715406262142976
1403715406312143104
1403715406362142976
1403715406412143104
1403715406462142976
1403715406512143104
1403715406562142976
1403715406612143104
1403715406662142976
1403715406712143104
1403715406762142976
1403715406812143104
1403715406862142976
1403715406912143104
1403715406962142976
1403715407012143104
1403715407062142976
1403715407112143104
1403715407162142976
1403715407212143104
1403715407262142976
1403715407312143104
1403715407362142976
1403715407412143104
1403715407462142976
1403715407512143104
1403715407562142976
1403715407612143104
1403715407662142976
1403715407712143104
1403715407762142976
1403715407812143104
1403715407862142976
1403715407912143104
1403715407962142976
1403715408012143104
1403715408062142976
1403715408112143104
1403715408162142976
1403715408212143104
1403715408262142976
1403715408312143104
1403715408362142976
1403715408412143104
1403715408462142976
1403715408512143104
1403715408562142976
1403715408612143104
1403715408662142976
1403715408712143104
1403715408762142976
1403715408812143104
1403715408862142976
1403715408912143104
1403715408962142976
1403715409012143104
1403715409062142976
1403715409112143104
1403715409162142976
1403715409212143104
1403715409262142976
1403715409312143104
1403715409362142976
1403715409412143104
1403715409462142976
1403715409512143104
1403715409562142976
1403715409612143104
1403715409662142976
1403715409712143104
1403715409762142976
1403715409812143104
1403715409862142976
1403715409912143104
1403715409962142976
1403715410012143104
1403715410062142976
1403715410112143104
1403715410162142976
1403715410212143104
1403715410262142976
1403715410312143104
1403715410362142976
1403715410412143104
1403715410462142976
1403715410512143104
1403715410562142976
1403715410612143104
1403715410662142976
1403715410712143104
1403715410762142976
1403715410812143104
1403715410862142976
1403715410912143104
1403715410962142976
1403715411012143104
1403715411062142976
1403715411112143104
1403715411162142976
1403715411212143104
1403715411262142976
1403715411312143104
1403715411362142976
1403715411412143104
1403715411462142976
1403715411512143104
1403715411562142976
1403715411612143104
1403715411662142976
1403715411712143104
1403715411762142976
1403715411812143104
1403715411862142976
1403715411912143104
1403715411962142976
1403715412012143104
1403715412062142976
1403715412112143104
1403715412162142976
1403715412212143104
1403715412262142976
1403715412312143104
1403715412362142976
1403715412412143104
1403715412462142976
1403715412512143104
1403715412562142976
1403715412612143104
1403715412662142976
1403715412712143104
1403715412762142976
1403715412812143104
1403715412862142976
1403715412912143104
1403715412962142976
1403715413012143104
1403715413062142976
1403715413112143104
1403715413162142976
1403715413212143104
1403715413262142976
1403715413312143104
1403715413362142976
1403715413412143104
1403715413462142976
1403715413512143104
1403715413562142976
1403715413612143104
1403715413662142976
1403715413712143104
1403715413762142976
1403715413812143104
1403715413862142976
1403715413912143104
1403715413962142976
1403715414012143104
1403715414062142976
1403715414112143104
1403715414162142976
1403715414212143104
1403715414262142976
1403715414312143104
1403715414362142976
1403715414412143104
1403715414462142976
1403715414512143104
1403715414562142976
1403715414612143104
1403715414662142976
1403715414712143104
1403715414762142976
1403715414812143104
1403715414862142976
1403715414912143104
1403715414962142976
1403715415012143104
1403715415062142976
1403715415112143104
1403715415162142976
1403715415212143104
1403715415262142976
1403715415312143104
1403715415362142976
1403715415412143104
1403715415462142976
1403715415512143104
1403715415562142976
1403715415612143104
1403715415662142976
1403715415712143104
1403715415762142976
1403715415812143104
1403715415862142976
1403715415912143104
1403715415962142976
1403715416012143104
1403715416062142976
1403715416112143104
1403715416162142976
1403715416212143104
1403715416262142976
1403715416312143104
1403715416362142976
1403715416412143104
1403715416462142976
1403715416512143104
1403715416562142976
1403715416612143104
1403715416662142976
1403715416712143104
1403715416762142976
1403715416812143104
1403715416862142976
1403715416912143104
1403715416962142976
1403715417012143104
1403715417062142976
1403715417112143104
1403715417162142976
1403715417212143104
1403715417262142976
1403715417312143104
1403715417362142976
1403715417412143104
1403715417462142976
1403715417512143104
1403715417562142976
1403715417612143104
1403715417662142976
1403715417712143104
1403715417762142976
1403715417812143104
1403715417862142976
1403715417912143104
1403715417962142976
1403715418012143104
1403715418062142976
1403715418112143104
1403715418162142976
1403715418212143104
1403715418262142976
1403715418312143104
1403715418362142976
1403715418412143104
1403715418462142976
1403715418512143104
1403715418562142976
1403715418612143104
1403715418662142976
1403715418712143104
1403715418762142976
1403715418812143104
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/V102.txt
================================================
1403715523912143104
1403715523962142976
1403715524012143104
1403715524062142976
1403715524112143104
1403715524162142976
1403715524212143104
1403715524262142976
1403715524312143104
1403715524362142976
1403715524412143104
1403715524462142976
1403715524512143104
1403715524562142976
1403715524612143104
1403715524662142976
1403715524712143104
1403715524762142976
1403715524812143104
1403715524862142976
1403715524912143104
1403715524962142976
1403715525012143104
1403715525062142976
1403715525112143104
1403715525162142976
1403715525212143104
1403715525262142976
1403715525312143104
1403715525362142976
1403715525412143104
1403715525462142976
1403715525512143104
1403715525562142976
1403715525612143104
1403715525662142976
1403715525712143104
1403715525762142976
1403715525812143104
1403715525862142976
1403715525912143104
1403715525962142976
1403715526012143104
1403715526062142976
1403715526112143104
1403715526162142976
1403715526212143104
1403715526262142976
1403715526312143104
1403715526362142976
1403715526412143104
1403715526462142976
1403715526512143104
1403715526562142976
1403715526612143104
1403715526662142976
1403715526712143104
1403715526762142976
1403715526812143104
1403715526862142976
1403715526912143104
1403715526962142976
1403715527012143104
1403715527062142976
1403715527112143104
1403715527162142976
1403715527212143104
1403715527262142976
1403715527312143104
1403715527362142976
1403715527412143104
1403715527462142976
1403715527512143104
1403715527562142976
1403715527612143104
1403715527662142976
1403715527712143104
1403715527762142976
1403715527812143104
1403715527862142976
1403715527912143104
1403715527962142976
1403715528012143104
1403715528062142976
1403715528112143104
1403715528162142976
1403715528212143104
1403715528262142976
1403715528312143104
1403715528362142976
1403715528412143104
1403715528462142976
1403715528512143104
1403715528562142976
1403715528612143104
1403715528662142976
1403715528712143104
1403715528762142976
1403715528812143104
1403715528862142976
1403715528912143104
1403715528962142976
1403715529012143104
1403715529062142976
1403715529112143104
1403715529162142976
1403715529212143104
1403715529262142976
1403715529312143104
1403715529362142976
1403715529412143104
1403715529462142976
1403715529512143104
1403715529562142976
1403715529612143104
1403715529662142976
1403715529712143104
1403715529762142976
1403715529812143104
1403715529862142976
1403715529912143104
1403715529962142976
1403715530012143104
1403715530062142976
1403715530112143104
1403715530162142976
1403715530212143104
1403715530262142976
1403715530312143104
1403715530362142976
1403715530412143104
1403715530462142976
1403715530512143104
1403715530562142976
1403715530612143104
1403715530662142976
1403715530712143104
1403715530762142976
1403715530812143104
1403715530862142976
1403715530912143104
1403715530962142976
1403715531012143104
1403715531062142976
1403715531112143104
1403715531162142976
1403715531212143104
1403715531262142976
1403715531312143104
1403715531362142976
1403715531412143104
1403715531462142976
1403715531512143104
1403715531562142976
1403715531612143104
1403715531662142976
1403715531712143104
1403715531762142976
1403715531812143104
1403715531862142976
1403715531912143104
1403715531962142976
1403715532012143104
1403715532062142976
1403715532112143104
1403715532162142976
1403715532212143104
1403715532262142976
1403715532312143104
1403715532362142976
1403715532412143104
1403715532462142976
1403715532512143104
1403715532562142976
1403715532612143104
1403715532662142976
1403715532712143104
1403715532762142976
1403715532812143104
1403715532862142976
1403715532912143104
1403715532962142976
1403715533012143104
1403715533062142976
1403715533112143104
1403715533162142976
1403715533212143104
1403715533262142976
1403715533312143104
1403715533362142976
1403715533412143104
1403715533462142976
1403715533512143104
1403715533562142976
1403715533612143104
1403715533662142976
1403715533712143104
1403715533762142976
1403715533812143104
1403715533862142976
1403715533912143104
1403715533962142976
1403715534012143104
1403715534062142976
1403715534112143104
1403715534162142976
1403715534212143104
1403715534262142976
1403715534312143104
1403715534362142976
1403715534412143104
1403715534462142976
1403715534512143104
1403715534562142976
1403715534612143104
1403715534662142976
1403715534712143104
1403715534762142976
1403715534812143104
1403715534862142976
1403715534912143104
1403715534962142976
1403715535012143104
1403715535062142976
1403715535112143104
1403715535162142976
1403715535212143104
1403715535262142976
1403715535312143104
1403715535362142976
1403715535412143104
1403715535462142976
1403715535512143104
1403715535562142976
1403715535612143104
1403715535662142976
1403715535712143104
1403715535762142976
1403715535812143104
1403715535862142976
1403715535912143104
1403715535962142976
1403715536012143104
1403715536062142976
1403715536112143104
1403715536162142976
1403715536212143104
1403715536262142976
1403715536312143104
1403715536362142976
1403715536412143104
1403715536462142976
1403715536512143104
1403715536562142976
1403715536612143104
1403715536662142976
1403715536712143104
1403715536762142976
1403715536812143104
1403715536862142976
1403715536912143104
1403715536962142976
1403715537012143104
1403715537062142976
1403715537112143104
1403715537162142976
1403715537212143104
1403715537262142976
1403715537312143104
1403715537362142976
1403715537412143104
1403715537462142976
1403715537512143104
1403715537562142976
1403715537612143104
1403715537662142976
1403715537712143104
1403715537762142976
1403715537812143104
1403715537862142976
1403715537912143104
1403715537962142976
1403715538012143104
1403715538062142976
1403715538112143104
1403715538162142976
1403715538212143104
1403715538262142976
1403715538312143104
1403715538362142976
1403715538412143104
1403715538462142976
1403715538512143104
1403715538562142976
1403715538612143104
1403715538662142976
1403715538712143104
1403715538762142976
1403715538812143104
1403715538862142976
1403715538912143104
1403715538962142976
1403715539012143104
1403715539062142976
1403715539112143104
1403715539162142976
1403715539212143104
1403715539262142976
1403715539312143104
1403715539362142976
1403715539412143104
1403715539462142976
1403715539512143104
1403715539562142976
1403715539612143104
1403715539662142976
1403715539712143104
1403715539762142976
1403715539812143104
1403715539862142976
1403715539912143104
1403715539962142976
1403715540012143104
1403715540062142976
1403715540112143104
1403715540162142976
1403715540212143104
1403715540262142976
1403715540312143104
1403715540362142976
1403715540412143104
1403715540462142976
1403715540512143104
1403715540562142976
1403715540612143104
1403715540662142976
1403715540712143104
1403715540762142976
1403715540812143104
1403715540862142976
1403715540912143104
1403715540962142976
1403715541012143104
1403715541062142976
1403715541112143104
1403715541162142976
1403715541212143104
1403715541262142976
1403715541312143104
1403715541362142976
1403715541412143104
1403715541462142976
1403715541512143104
1403715541562142976
1403715541612143104
1403715541662142976
1403715541712143104
1403715541762142976
1403715541812143104
1403715541862142976
1403715541912143104
1403715541962142976
1403715542012143104
1403715542062142976
1403715542112143104
1403715542162142976
1403715542212143104
1403715542262142976
1403715542312143104
1403715542362142976
1403715542412143104
1403715542462142976
1403715542512143104
1403715542562142976
1403715542612143104
1403715542662142976
1403715542712143104
1403715542762142976
1403715542812143104
1403715542862142976
1403715542912143104
1403715542962142976
1403715543012143104
1403715543062142976
1403715543112143104
1403715543162142976
1403715543212143104
1403715543262142976
1403715543312143104
1403715543362142976
1403715543412143104
1403715543462142976
1403715543512143104
1403715543562142976
1403715543612143104
1403715543662142976
1403715543712143104
1403715543762142976
1403715543812143104
1403715543862142976
1403715543912143104
1403715543962142976
1403715544012143104
1403715544062142976
1403715544112143104
1403715544162142976
1403715544212143104
1403715544262142976
1403715544312143104
1403715544362142976
1403715544412143104
1403715544462142976
1403715544512143104
1403715544562142976
1403715544612143104
1403715544662142976
1403715544712143104
1403715544762142976
1403715544812143104
1403715544862142976
1403715544912143104
1403715544962142976
1403715545012143104
1403715545062142976
1403715545112143104
1403715545162142976
1403715545212143104
1403715545262142976
1403715545312143104
1403715545362142976
1403715545412143104
1403715545462142976
1403715545512143104
1403715545562142976
1403715545612143104
1403715545662142976
1403715545712143104
1403715545762142976
1403715545812143104
1403715545862142976
1403715545912143104
1403715545962142976
1403715546012143104
1403715546062142976
1403715546112143104
1403715546162142976
1403715546212143104
1403715546262142976
1403715546312143104
1403715546362142976
1403715546412143104
1403715546462142976
1403715546512143104
1403715546562142976
1403715546612143104
1403715546662142976
1403715546712143104
1403715546762142976
1403715546812143104
1403715546862142976
1403715546912143104
1403715546962142976
1403715547012143104
1403715547062142976
1403715547112143104
1403715547162142976
1403715547212143104
1403715547262142976
1403715547312143104
1403715547362142976
1403715547412143104
1403715547462142976
1403715547512143104
1403715547562142976
1403715547612143104
1403715547662142976
1403715547712143104
1403715547762142976
1403715547812143104
1403715547862142976
1403715547912143104
1403715547962142976
1403715548012143104
1403715548062142976
1403715548112143104
1403715548162142976
1403715548212143104
1403715548262142976
1403715548312143104
1403715548362142976
1403715548412143104
1403715548462142976
1403715548512143104
1403715548562142976
1403715548612143104
1403715548662142976
1403715548712143104
1403715548762142976
1403715548812143104
1403715548862142976
1403715548912143104
1403715548962142976
1403715549012143104
1403715549062142976
1403715549112143104
1403715549162142976
1403715549212143104
1403715549262142976
1403715549312143104
1403715549362142976
1403715549412143104
1403715549462142976
1403715549512143104
1403715549562142976
1403715549612143104
1403715549662142976
1403715549712143104
1403715549762142976
1403715549812143104
1403715549862142976
1403715549912143104
1403715549962142976
1403715550012143104
1403715550062142976
1403715550112143104
1403715550162142976
1403715550212143104
1403715550262142976
1403715550312143104
1403715550362142976
1403715550412143104
1403715550462142976
1403715550512143104
1403715550562142976
1403715550612143104
1403715550662142976
1403715550712143104
1403715550762142976
1403715550812143104
1403715550862142976
1403715550912143104
1403715550962142976
1403715551012143104
1403715551062142976
1403715551112143104
1403715551162142976
1403715551212143104
1403715551262142976
1403715551312143104
1403715551362142976
1403715551412143104
1403715551462142976
1403715551512143104
1403715551562142976
1403715551612143104
1403715551662142976
1403715551712143104
1403715551762142976
1403715551812143104
1403715551862142976
1403715551912143104
1403715551962142976
1403715552012143104
1403715552062142976
1403715552112143104
1403715552162142976
1403715552212143104
1403715552262142976
1403715552312143104
1403715552362142976
1403715552412143104
1403715552462142976
1403715552512143104
1403715552562142976
1403715552612143104
1403715552662142976
1403715552712143104
1403715552762142976
1403715552812143104
1403715552862142976
1403715552912143104
1403715552962142976
1403715553012143104
1403715553062142976
1403715553112143104
1403715553162142976
1403715553212143104
1403715553262142976
1403715553312143104
1403715553362142976
1403715553412143104
1403715553462142976
1403715553512143104
1403715553562142976
1403715553612143104
1403715553662142976
1403715553712143104
1403715553762142976
1403715553812143104
1403715553862142976
1403715553912143104
1403715553962142976
1403715554012143104
1403715554062142976
1403715554112143104
1403715554162142976
1403715554212143104
1403715554262142976
1403715554312143104
1403715554362142976
1403715554412143104
1403715554462142976
1403715554512143104
1403715554562142976
1403715554612143104
1403715554662142976
1403715554712143104
1403715554762142976
1403715554812143104
1403715554862142976
1403715554912143104
1403715554962142976
1403715555012143104
1403715555062142976
1403715555112143104
1403715555162142976
1403715555212143104
1403715555262142976
1403715555312143104
1403715555362142976
1403715555412143104
1403715555462142976
1403715555512143104
1403715555562142976
1403715555612143104
1403715555662142976
1403715555712143104
1403715555762142976
1403715555812143104
1403715555862142976
1403715555912143104
1403715555962142976
1403715556012143104
1403715556062142976
1403715556112143104
1403715556162142976
1403715556212143104
1403715556262142976
1403715556312143104
1403715556362142976
1403715556412143104
1403715556462142976
1403715556512143104
1403715556562142976
1403715556612143104
1403715556662142976
1403715556712143104
1403715556762142976
1403715556812143104
1403715556862142976
1403715556912143104
1403715556962142976
1403715557012143104
1403715557062142976
1403715557112143104
1403715557162142976
1403715557212143104
1403715557262142976
1403715557312143104
1403715557362142976
1403715557412143104
1403715557462142976
1403715557512143104
1403715557562142976
1403715557612143104
1403715557662142976
1403715557712143104
1403715557762142976
1403715557812143104
1403715557862142976
1403715557912143104
1403715557962142976
1403715558012143104
1403715558062142976
1403715558112143104
1403715558162142976
1403715558212143104
1403715558262142976
1403715558312143104
1403715558362142976
1403715558412143104
1403715558462142976
1403715558512143104
1403715558562142976
1403715558612143104
1403715558662142976
1403715558712143104
1403715558762142976
1403715558812143104
1403715558862142976
1403715558912143104
1403715558962142976
1403715559012143104
1403715559062142976
1403715559112143104
1403715559162142976
1403715559212143104
1403715559262142976
1403715559312143104
1403715559362142976
1403715559412143104
1403715559462142976
1403715559512143104
1403715559562142976
1403715559612143104
1403715559662142976
1403715559712143104
1403715559762142976
1403715559812143104
1403715559862142976
1403715559912143104
1403715559962142976
1403715560012143104
1403715560062142976
1403715560112143104
1403715560162142976
1403715560212143104
1403715560262142976
1403715560312143104
1403715560362142976
1403715560412143104
1403715560462142976
1403715560512143104
1403715560562142976
1403715560612143104
1403715560662142976
1403715560712143104
1403715560762142976
1403715560812143104
1403715560862142976
1403715560912143104
1403715560962142976
1403715561012143104
1403715561062142976
1403715561112143104
1403715561162142976
1403715561212143104
1403715561262142976
1403715561312143104
1403715561362142976
1403715561412143104
1403715561462142976
1403715561512143104
1403715561562142976
1403715561612143104
1403715561662142976
1403715561712143104
1403715561762142976
1403715561812143104
1403715561862142976
1403715561912143104
1403715561962142976
1403715562012143104
1403715562062142976
1403715562112143104
1403715562162142976
1403715562212143104
1403715562262142976
1403715562312143104
1403715562362142976
1403715562412143104
1403715562462142976
1403715562512143104
1403715562562142976
1403715562612143104
1403715562662142976
1403715562712143104
1403715562762142976
1403715562812143104
1403715562862142976
1403715562912143104
1403715562962142976
1403715563012143104
1403715563062142976
1403715563112143104
1403715563162142976
1403715563212143104
1403715563262142976
1403715563312143104
1403715563362142976
1403715563412143104
1403715563462142976
1403715563512143104
1403715563562142976
1403715563612143104
1403715563662142976
1403715563712143104
1403715563762142976
1403715563812143104
1403715563862142976
1403715563912143104
1403715563962142976
1403715564012143104
1403715564062142976
1403715564112143104
1403715564162142976
1403715564212143104
1403715564262142976
1403715564312143104
1403715564362142976
1403715564412143104
1403715564462142976
1403715564512143104
1403715564562142976
1403715564612143104
1403715564662142976
1403715564712143104
1403715564762142976
1403715564812143104
1403715564862142976
1403715564912143104
1403715564962142976
1403715565012143104
1403715565062142976
1403715565112143104
1403715565162142976
1403715565212143104
1403715565262142976
1403715565312143104
1403715565362142976
1403715565412143104
1403715565462142976
1403715565512143104
1403715565562142976
1403715565612143104
1403715565662142976
1403715565712143104
1403715565762142976
1403715565812143104
1403715565862142976
1403715565912143104
1403715565962142976
1403715566012143104
1403715566062142976
1403715566112143104
1403715566162142976
1403715566212143104
1403715566262142976
1403715566312143104
1403715566362142976
1403715566412143104
1403715566462142976
1403715566512143104
1403715566562142976
1403715566612143104
1403715566662142976
1403715566712143104
1403715566762142976
1403715566812143104
1403715566862142976
1403715566912143104
1403715566962142976
1403715567012143104
1403715567062142976
1403715567112143104
1403715567162142976
1403715567212143104
1403715567262142976
1403715567312143104
1403715567362142976
1403715567412143104
1403715567462142976
1403715567512143104
1403715567562142976
1403715567612143104
1403715567662142976
1403715567712143104
1403715567762142976
1403715567812143104
1403715567862142976
1403715567912143104
1403715567962142976
1403715568012143104
1403715568062142976
1403715568112143104
1403715568162142976
1403715568212143104
1403715568262142976
1403715568312143104
1403715568362142976
1403715568412143104
1403715568462142976
1403715568512143104
1403715568562142976
1403715568612143104
1403715568662142976
1403715568712143104
1403715568762142976
1403715568812143104
1403715568862142976
1403715568912143104
1403715568962142976
1403715569012143104
1403715569062142976
1403715569112143104
1403715569162142976
1403715569212143104
1403715569262142976
1403715569312143104
1403715569362142976
1403715569412143104
1403715569462142976
1403715569512143104
1403715569562142976
1403715569612143104
1403715569662142976
1403715569712143104
1403715569762142976
1403715569812143104
1403715569862142976
1403715569912143104
1403715569962142976
1403715570012143104
1403715570062142976
1403715570112143104
1403715570162142976
1403715570212143104
1403715570262142976
1403715570312143104
1403715570362142976
1403715570412143104
1403715570462142976
1403715570512143104
1403715570562142976
1403715570612143104
1403715570662142976
1403715570712143104
1403715570762142976
1403715570812143104
1403715570862142976
1403715570912143104
1403715570962142976
1403715571012143104
1403715571062142976
1403715571112143104
1403715571162142976
1403715571212143104
1403715571262142976
1403715571312143104
1403715571362142976
1403715571412143104
1403715571462142976
1403715571512143104
1403715571562142976
1403715571612143104
1403715571662142976
1403715571712143104
1403715571762142976
1403715571812143104
1403715571862142976
1403715571912143104
1403715571962142976
1403715572012143104
1403715572062142976
1403715572112143104
1403715572162142976
1403715572212143104
1403715572262142976
1403715572312143104
1403715572362142976
1403715572412143104
1403715572462142976
1403715572512143104
1403715572562142976
1403715572612143104
1403715572662142976
1403715572712143104
1403715572762142976
1403715572812143104
1403715572862142976
1403715572912143104
1403715572962142976
1403715573012143104
1403715573062142976
1403715573112143104
1403715573162142976
1403715573212143104
1403715573262142976
1403715573312143104
1403715573362142976
1403715573412143104
1403715573462142976
1403715573512143104
1403715573562142976
1403715573612143104
1403715573662142976
1403715573712143104
1403715573762142976
1403715573812143104
1403715573862142976
1403715573912143104
1403715573962142976
1403715574012143104
1403715574062142976
1403715574112143104
1403715574162142976
1403715574212143104
1403715574262142976
1403715574312143104
1403715574362142976
1403715574412143104
1403715574462142976
1403715574512143104
1403715574562142976
1403715574612143104
1403715574662142976
1403715574712143104
1403715574762142976
1403715574812143104
1403715574862142976
1403715574912143104
1403715574962142976
1403715575012143104
1403715575062142976
1403715575112143104
1403715575162142976
1403715575212143104
1403715575262142976
1403715575312143104
1403715575362142976
1403715575412143104
1403715575462142976
1403715575512143104
1403715575562142976
1403715575612143104
1403715575662142976
1403715575712143104
1403715575762142976
1403715575812143104
1403715575862142976
1403715575912143104
1403715575962142976
1403715576012143104
1403715576062142976
1403715576112143104
1403715576162142976
1403715576212143104
1403715576262142976
1403715576312143104
1403715576362142976
1403715576412143104
1403715576462142976
1403715576512143104
1403715576562142976
1403715576612143104
1403715576662142976
1403715576712143104
1403715576762142976
1403715576812143104
1403715576862142976
1403715576912143104
1403715576962142976
1403715577012143104
1403715577062142976
1403715577112143104
1403715577162142976
1403715577212143104
1403715577262142976
1403715577312143104
1403715577362142976
1403715577412143104
1403715577462142976
1403715577512143104
1403715577562142976
1403715577612143104
1403715577662142976
1403715577712143104
1403715577762142976
1403715577812143104
1403715577862142976
1403715577912143104
1403715577962142976
1403715578012143104
1403715578062142976
1403715578112143104
1403715578162142976
1403715578212143104
1403715578262142976
1403715578312143104
1403715578362142976
1403715578412143104
1403715578462142976
1403715578512143104
1403715578562142976
1403715578612143104
1403715578662142976
1403715578712143104
1403715578762142976
1403715578812143104
1403715578862142976
1403715578912143104
1403715578962142976
1403715579012143104
1403715579062142976
1403715579112143104
1403715579162142976
1403715579212143104
1403715579262142976
1403715579312143104
1403715579362142976
1403715579412143104
1403715579462142976
1403715579512143104
1403715579562142976
1403715579612143104
1403715579662142976
1403715579712143104
1403715579762142976
1403715579812143104
1403715579862142976
1403715579912143104
1403715579962142976
1403715580012143104
1403715580062142976
1403715580112143104
1403715580162142976
1403715580212143104
1403715580262142976
1403715580312143104
1403715580362142976
1403715580412143104
1403715580462142976
1403715580512143104
1403715580562142976
1403715580612143104
1403715580662142976
1403715580712143104
1403715580762142976
1403715580812143104
1403715580862142976
1403715580912143104
1403715580962142976
1403715581012143104
1403715581062142976
1403715581112143104
1403715581162142976
1403715581212143104
1403715581262142976
1403715581312143104
1403715581362142976
1403715581412143104
1403715581462142976
1403715581512143104
1403715581562142976
1403715581612143104
1403715581662142976
1403715581712143104
1403715581762142976
1403715581812143104
1403715581862142976
1403715581912143104
1403715581962142976
1403715582012143104
1403715582062142976
1403715582112143104
1403715582162142976
1403715582212143104
1403715582262142976
1403715582312143104
1403715582362142976
1403715582412143104
1403715582462142976
1403715582512143104
1403715582562142976
1403715582612143104
1403715582662142976
1403715582712143104
1403715582762142976
1403715582812143104
1403715582862142976
1403715582912143104
1403715582962142976
1403715583012143104
1403715583062142976
1403715583112143104
1403715583162142976
1403715583212143104
1403715583262142976
1403715583312143104
1403715583362142976
1403715583412143104
1403715583462142976
1403715583512143104
1403715583562142976
1403715583612143104
1403715583662142976
1403715583712143104
1403715583762142976
1403715583812143104
1403715583862142976
1403715583912143104
1403715583962142976
1403715584012143104
1403715584062142976
1403715584112143104
1403715584162142976
1403715584212143104
1403715584262142976
1403715584312143104
1403715584362142976
1403715584412143104
1403715584462142976
1403715584512143104
1403715584562142976
1403715584612143104
1403715584662142976
1403715584712143104
1403715584762142976
1403715584812143104
1403715584862142976
1403715584912143104
1403715584962142976
1403715585012143104
1403715585062142976
1403715585112143104
1403715585162142976
1403715585212143104
1403715585262142976
1403715585312143104
1403715585362142976
1403715585412143104
1403715585462142976
1403715585512143104
1403715585562142976
1403715585612143104
1403715585662142976
1403715585712143104
1403715585762142976
1403715585812143104
1403715585862142976
1403715585912143104
1403715585962142976
1403715586012143104
1403715586062142976
1403715586112143104
1403715586162142976
1403715586212143104
1403715586262142976
1403715586312143104
1403715586362142976
1403715586412143104
1403715586462142976
1403715586512143104
1403715586562142976
1403715586612143104
1403715586662142976
1403715586712143104
1403715586762142976
1403715586812143104
1403715586862142976
1403715586912143104
1403715586962142976
1403715587012143104
1403715587062142976
1403715587112143104
1403715587162142976
1403715587212143104
1403715587262142976
1403715587312143104
1403715587362142976
1403715587412143104
1403715587462142976
1403715587512143104
1403715587562142976
1403715587612143104
1403715587662142976
1403715587712143104
1403715587762142976
1403715587812143104
1403715587862142976
1403715587912143104
1403715587962142976
1403715588012143104
1403715588062142976
1403715588112143104
1403715588162142976
1403715588212143104
1403715588262142976
1403715588312143104
1403715588362142976
1403715588412143104
1403715588462142976
1403715588512143104
1403715588562142976
1403715588612143104
1403715588662142976
1403715588712143104
1403715588762142976
1403715588812143104
1403715588862142976
1403715588912143104
1403715588962142976
1403715589012143104
1403715589062142976
1403715589112143104
1403715589162142976
1403715589212143104
1403715589262142976
1403715589312143104
1403715589362142976
1403715589412143104
1403715589462142976
1403715589512143104
1403715589562142976
1403715589612143104
1403715589662142976
1403715589712143104
1403715589762142976
1403715589812143104
1403715589862142976
1403715589912143104
1403715589962142976
1403715590012143104
1403715590062142976
1403715590112143104
1403715590162142976
1403715590212143104
1403715590262142976
1403715590312143104
1403715590362142976
1403715590412143104
1403715590462142976
1403715590512143104
1403715590562142976
1403715590612143104
1403715590662142976
1403715590712143104
1403715590762142976
1403715590812143104
1403715590862142976
1403715590912143104
1403715590962142976
1403715591012143104
1403715591062142976
1403715591112143104
1403715591162142976
1403715591212143104
1403715591262142976
1403715591312143104
1403715591362142976
1403715591412143104
1403715591462142976
1403715591512143104
1403715591562142976
1403715591612143104
1403715591662142976
1403715591712143104
1403715591762142976
1403715591812143104
1403715591862142976
1403715591912143104
1403715591962142976
1403715592012143104
1403715592062142976
1403715592112143104
1403715592162142976
1403715592212143104
1403715592262142976
1403715592312143104
1403715592362142976
1403715592412143104
1403715592462142976
1403715592512143104
1403715592562142976
1403715592612143104
1403715592662142976
1403715592712143104
1403715592762142976
1403715592812143104
1403715592862142976
1403715592912143104
1403715592962142976
1403715593012143104
1403715593062142976
1403715593112143104
1403715593162142976
1403715593212143104
1403715593262142976
1403715593312143104
1403715593362142976
1403715593412143104
1403715593462142976
1403715593512143104
1403715593562142976
1403715593612143104
1403715593662142976
1403715593712143104
1403715593762142976
1403715593812143104
1403715593862142976
1403715593912143104
1403715593962142976
1403715594012143104
1403715594062142976
1403715594112143104
1403715594162142976
1403715594212143104
1403715594262142976
1403715594312143104
1403715594362142976
1403715594412143104
1403715594462142976
1403715594512143104
1403715594562142976
1403715594612143104
1403715594662142976
1403715594712143104
1403715594762142976
1403715594812143104
1403715594862142976
1403715594912143104
1403715594962142976
1403715595012143104
1403715595062142976
1403715595112143104
1403715595162142976
1403715595212143104
1403715595262142976
1403715595312143104
1403715595362142976
1403715595412143104
1403715595462142976
1403715595512143104
1403715595562142976
1403715595612143104
1403715595662142976
1403715595712143104
1403715595762142976
1403715595812143104
1403715595862142976
1403715595912143104
1403715595962142976
1403715596012143104
1403715596062142976
1403715596112143104
1403715596162142976
1403715596212143104
1403715596262142976
1403715596312143104
1403715596362142976
1403715596412143104
1403715596462142976
1403715596512143104
1403715596562142976
1403715596612143104
1403715596662142976
1403715596712143104
1403715596762142976
1403715596812143104
1403715596862142976
1403715596912143104
1403715596962142976
1403715597012143104
1403715597062142976
1403715597112143104
1403715597162142976
1403715597212143104
1403715597262142976
1403715597312143104
1403715597362142976
1403715597412143104
1403715597462142976
1403715597512143104
1403715597562142976
1403715597612143104
1403715597662142976
1403715597712143104
1403715597762142976
1403715597812143104
1403715597862142976
1403715597912143104
1403715597962142976
1403715598012143104
1403715598062142976
1403715598112143104
1403715598162142976
1403715598212143104
1403715598262142976
1403715598312143104
1403715598362142976
1403715598412143104
1403715598462142976
1403715598512143104
1403715598562142976
1403715598612143104
1403715598662142976
1403715598712143104
1403715598762142976
1403715598812143104
1403715598862142976
1403715598912143104
1403715598962142976
1403715599012143104
1403715599062142976
1403715599112143104
1403715599162142976
1403715599212143104
1403715599262142976
1403715599312143104
1403715599362142976
1403715599412143104
1403715599462142976
1403715599512143104
1403715599562142976
1403715599612143104
1403715599662142976
1403715599712143104
1403715599762142976
1403715599812143104
1403715599862142976
1403715599912143104
1403715599962142976
1403715600012143104
1403715600062142976
1403715600112143104
1403715600162142976
1403715600212143104
1403715600262142976
1403715600312143104
1403715600362142976
1403715600412143104
1403715600462142976
1403715600512143104
1403715600562142976
1403715600612143104
1403715600662142976
1403715600712143104
1403715600762142976
1403715600812143104
1403715600862142976
1403715600912143104
1403715600962142976
1403715601012143104
1403715601062142976
1403715601112143104
1403715601162142976
1403715601212143104
1403715601262142976
1403715601312143104
1403715601362142976
1403715601412143104
1403715601462142976
1403715601512143104
1403715601562142976
1403715601612143104
1403715601662142976
1403715601712143104
1403715601762142976
1403715601812143104
1403715601862142976
1403715601912143104
1403715601962142976
1403715602012143104
1403715602062142976
1403715602112143104
1403715602162142976
1403715602212143104
1403715602262142976
1403715602312143104
1403715602362142976
1403715602412143104
1403715602462142976
1403715602512143104
1403715602562142976
1403715602612143104
1403715602662142976
1403715602712143104
1403715602762142976
1403715602812143104
1403715602862142976
1403715602912143104
1403715602962142976
1403715603012143104
1403715603062142976
1403715603112143104
1403715603162142976
1403715603212143104
1403715603262142976
1403715603312143104
1403715603362142976
1403715603412143104
1403715603462142976
1403715603512143104
1403715603562142976
1403715603612143104
1403715603662142976
1403715603712143104
1403715603762142976
1403715603812143104
1403715603862142976
1403715603912143104
1403715603962142976
1403715604012143104
1403715604062142976
1403715604112143104
1403715604162142976
1403715604212143104
1403715604262142976
1403715604312143104
1403715604362142976
1403715604412143104
1403715604462142976
1403715604512143104
1403715604562142976
1403715604612143104
1403715604662142976
1403715604712143104
1403715604762142976
1403715604812143104
1403715604862142976
1403715604912143104
1403715604962142976
1403715605012143104
1403715605062142976
1403715605112143104
1403715605162142976
1403715605212143104
1403715605262142976
1403715605312143104
1403715605362142976
1403715605412143104
1403715605462142976
1403715605512143104
1403715605562142976
1403715605612143104
1403715605662142976
1403715605712143104
1403715605762142976
1403715605812143104
1403715605862142976
1403715605912143104
1403715605962142976
1403715606012143104
1403715606062142976
1403715606112143104
1403715606162142976
1403715606212143104
1403715606262142976
1403715606312143104
1403715606362142976
1403715606412143104
1403715606462142976
1403715606512143104
1403715606562142976
1403715606612143104
1403715606662142976
1403715606712143104
1403715606762142976
1403715606812143104
1403715606862142976
1403715606912143104
1403715606962142976
1403715607012143104
1403715607062142976
1403715607112143104
1403715607162142976
1403715607212143104
1403715607262142976
1403715607312143104
1403715607362142976
1403715607412143104
1403715607462142976
1403715607512143104
1403715607562142976
1403715607612143104
1403715607662142976
1403715607712143104
1403715607762142976
1403715607812143104
1403715607862142976
1403715607912143104
1403715607962142976
1403715608012143104
1403715608062142976
1403715608112143104
1403715608162142976
1403715608212143104
1403715608262142976
1403715608312143104
1403715608362142976
1403715608412143104
1403715608462142976
1403715608512143104
1403715608562142976
1403715608612143104
1403715608662142976
1403715608712143104
1403715608762142976
1403715608812143104
1403715608862142976
1403715608912143104
1403715608962142976
1403715609012143104
1403715609062142976
1403715609112143104
1403715609162142976
1403715609212143104
1403715609262142976
1403715609312143104
1403715609362142976
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/V103.txt
================================================
1403715886584058112
1403715886634057984
1403715886684058112
1403715886734057984
1403715886784058112
1403715886834057984
1403715886884058112
1403715886934057984
1403715886984058112
1403715887034057984
1403715887084058112
1403715887134057984
1403715887184058112
1403715887234057984
1403715887284058112
1403715887334057984
1403715887384058112
1403715887434057984
1403715887484058112
1403715887534057984
1403715887584058112
1403715887634057984
1403715887684058112
1403715887734057984
1403715887784058112
1403715887834057984
1403715887884058112
1403715887934057984
1403715887984058112
1403715888034057984
1403715888084058112
1403715888134057984
1403715888184058112
1403715888234057984
1403715888284058112
1403715888334057984
1403715888384058112
1403715888434057984
1403715888484058112
1403715888534057984
1403715888584058112
1403715888634057984
1403715888684058112
1403715888734057984
1403715888784058112
1403715888834057984
1403715888884058112
1403715888934057984
1403715888984058112
1403715889034057984
1403715889084058112
1403715889134057984
1403715889184058112
1403715889234057984
1403715889284058112
1403715889334057984
1403715889384058112
1403715889434057984
1403715889484058112
1403715889534057984
1403715889584058112
1403715889634057984
1403715889684058112
1403715889734057984
1403715889784058112
1403715889834057984
1403715889884058112
1403715889934057984
1403715889984058112
1403715890034057984
1403715890084058112
1403715890134057984
1403715890184058112
1403715890234057984
1403715890284058112
1403715890334057984
1403715890384058112
1403715890434057984
1403715890484058112
1403715890534057984
1403715890584058112
1403715890634057984
1403715890684058112
1403715890734057984
1403715890784058112
1403715890834057984
1403715890884058112
1403715890934057984
1403715890984058112
1403715891034057984
1403715891084058112
1403715891134057984
1403715891184058112
1403715891234057984
1403715891284058112
1403715891334057984
1403715891384058112
1403715891434057984
1403715891484058112
1403715891534057984
1403715891584058112
1403715891634057984
1403715891684058112
1403715891734057984
1403715891784058112
1403715891834057984
1403715891884058112
1403715891934057984
1403715891984058112
1403715892034057984
1403715892084058112
1403715892134057984
1403715892184058112
1403715892234057984
1403715892284058112
1403715892334057984
1403715892384058112
1403715892434057984
1403715892484058112
1403715892534057984
1403715892584058112
1403715892634057984
1403715892684058112
1403715892734057984
1403715892784058112
1403715892834057984
1403715892884058112
1403715892934057984
1403715892984058112
1403715893034057984
1403715893084058112
1403715893134057984
1403715893184058112
1403715893234057984
1403715893284058112
1403715893334057984
1403715893384058112
1403715893434057984
1403715893484058112
1403715893534057984
1403715893584058112
1403715893634057984
1403715893684058112
1403715893734057984
1403715893784058112
1403715893834057984
1403715893884058112
1403715893934057984
1403715893984058112
1403715894034057984
1403715894084058112
1403715894134057984
1403715894184058112
1403715894234057984
1403715894284058112
1403715894334057984
1403715894384058112
1403715894434057984
1403715894484058112
1403715894534057984
1403715894584058112
1403715894634057984
1403715894684058112
1403715894734057984
1403715894784058112
1403715894834057984
1403715894884058112
1403715894934057984
1403715894984058112
1403715895034057984
1403715895084058112
1403715895134057984
1403715895184058112
1403715895234057984
1403715895284058112
1403715895334057984
1403715895384058112
1403715895434057984
1403715895484058112
1403715895534057984
1403715895584058112
1403715895634057984
1403715895684058112
1403715895734057984
1403715895784058112
1403715895834057984
1403715895884058112
1403715895934057984
1403715895984058112
1403715896034057984
1403715896084058112
1403715896134057984
1403715896184058112
1403715896234057984
1403715896284058112
1403715896334057984
1403715896384058112
1403715896434057984
1403715896484058112
1403715896534057984
1403715896584058112
1403715896634057984
1403715896684058112
1403715896734057984
1403715896784058112
1403715896834057984
1403715896884058112
1403715896934057984
1403715896984058112
1403715897034057984
1403715897084058112
1403715897134057984
1403715897184058112
1403715897234057984
1403715897284058112
1403715897334057984
1403715897384058112
1403715897434057984
1403715897484058112
1403715897534057984
1403715897584058112
1403715897634057984
1403715897684058112
1403715897734057984
1403715897784058112
1403715897834057984
1403715897884058112
1403715897934057984
1403715897984058112
1403715898034057984
1403715898084058112
1403715898134057984
1403715898184058112
1403715898234057984
1403715898284058112
1403715898334057984
1403715898384058112
1403715898434057984
1403715898484058112
1403715898534057984
1403715898584058112
1403715898634057984
1403715898684058112
1403715898734057984
1403715898784058112
1403715898834057984
1403715898884058112
1403715898934057984
1403715898984058112
1403715899034057984
1403715899084058112
1403715899134057984
1403715899184058112
1403715899234057984
1403715899284058112
1403715899334057984
1403715899384058112
1403715899434057984
1403715899484058112
1403715899534057984
1403715899584058112
1403715899634057984
1403715899684058112
1403715899734057984
1403715899784058112
1403715899834057984
1403715899884058112
1403715899934057984
1403715899984058112
1403715900034057984
1403715900084058112
1403715900134057984
1403715900184058112
1403715900234057984
1403715900284058112
1403715900334057984
1403715900384058112
1403715900434057984
1403715900484058112
1403715900534057984
1403715900584058112
1403715900634057984
1403715900684058112
1403715900734057984
1403715900784058112
1403715900834057984
1403715900884058112
1403715900934057984
1403715900984058112
1403715901034057984
1403715901084058112
1403715901134057984
1403715901184058112
1403715901234057984
1403715901284058112
1403715901334057984
1403715901384058112
1403715901434057984
1403715901484058112
1403715901534057984
1403715901584058112
1403715901634057984
1403715901684058112
1403715901734057984
1403715901784058112
1403715901834057984
1403715901884058112
1403715901934057984
1403715901984058112
1403715902034057984
1403715902084058112
1403715902134057984
1403715902184058112
1403715902234057984
1403715902284058112
1403715902334057984
1403715902384058112
1403715902434057984
1403715902484058112
1403715902534057984
1403715902584058112
1403715902634057984
1403715902684058112
1403715902734057984
1403715902784058112
1403715902834057984
1403715902884058112
1403715902934057984
1403715902984058112
1403715903034057984
1403715903084058112
1403715903134057984
1403715903184058112
1403715903234057984
1403715903284058112
1403715903334057984
1403715903384058112
1403715903434057984
1403715903484058112
1403715903534057984
1403715903584058112
1403715903634057984
1403715903684058112
1403715903734057984
1403715903784058112
1403715903834057984
1403715903884058112
1403715903934057984
1403715903984058112
1403715904034057984
1403715904084058112
1403715904134057984
1403715904184058112
1403715904234057984
1403715904284058112
1403715904334057984
1403715904384058112
1403715904434057984
1403715904484058112
1403715904534057984
1403715904584058112
1403715904634057984
1403715904684058112
1403715904734057984
1403715904784058112
1403715904834057984
1403715904884058112
1403715904934057984
1403715904984058112
1403715905034057984
1403715905084058112
1403715905134057984
1403715905184058112
1403715905234057984
1403715905284058112
1403715905334057984
1403715905384058112
1403715905434057984
1403715905484058112
1403715905534057984
1403715905584058112
1403715905634057984
1403715905684058112
1403715905734057984
1403715905784058112
1403715905834057984
1403715905884058112
1403715905934057984
1403715905984058112
1403715906034057984
1403715906084058112
1403715906134057984
1403715906184058112
1403715906234057984
1403715906284058112
1403715906334057984
1403715906384058112
1403715906434057984
1403715906484058112
1403715906534057984
1403715906584058112
1403715906634057984
1403715906684058112
1403715906734057984
1403715906784058112
1403715906834057984
1403715906884058112
1403715906934057984
1403715906984058112
1403715907034057984
1403715907084058112
1403715907134057984
1403715907184058112
1403715907234057984
1403715907284058112
1403715907334057984
1403715907384058112
1403715907434057984
1403715907484058112
1403715907534057984
1403715907584058112
1403715907634057984
1403715907684058112
1403715907734057984
1403715907784058112
1403715907834057984
1403715907884058112
1403715907934057984
1403715907984058112
1403715908034057984
1403715908084058112
1403715908134057984
1403715908184058112
1403715908234057984
1403715908284058112
1403715908334057984
1403715908384058112
1403715908434057984
1403715908484058112
1403715908534057984
1403715908584058112
1403715908634057984
1403715908684058112
1403715908734057984
1403715908784058112
1403715908834057984
1403715908884058112
1403715908934057984
1403715908984058112
1403715909034057984
1403715909084058112
1403715909134057984
1403715909184058112
1403715909234057984
1403715909284058112
1403715909334057984
1403715909384058112
1403715909434057984
1403715909484058112
1403715909534057984
1403715909584058112
1403715909634057984
1403715909684058112
1403715909734057984
1403715909784058112
1403715909834057984
1403715909884058112
1403715909934057984
1403715909984058112
1403715910034057984
1403715910084058112
1403715910134057984
1403715910184058112
1403715910234057984
1403715910284058112
1403715910334057984
1403715910384058112
1403715910434057984
1403715910484058112
1403715910534057984
1403715910584058112
1403715910634057984
1403715910684058112
1403715910734057984
1403715910784058112
1403715910834057984
1403715910884058112
1403715910934057984
1403715910984058112
1403715911034057984
1403715911084058112
1403715911134057984
1403715911184058112
1403715911234057984
1403715911284058112
1403715911334057984
1403715911384058112
1403715911434057984
1403715911484058112
1403715911534057984
1403715911584058112
1403715911634057984
1403715911684058112
1403715911734057984
1403715911784058112
1403715911834057984
1403715911884058112
1403715911934057984
1403715911984058112
1403715912034057984
1403715912084058112
1403715912134057984
1403715912184058112
1403715912234057984
1403715912284058112
1403715912334057984
1403715912384058112
1403715912434057984
1403715912484058112
1403715912534057984
1403715912584058112
1403715912634057984
1403715912684058112
1403715912734057984
1403715912784058112
1403715912834057984
1403715912884058112
1403715912934057984
1403715912984058112
1403715913034057984
1403715913084058112
1403715913134057984
1403715913184058112
1403715913234057984
1403715913284058112
1403715913334057984
1403715913384058112
1403715913434057984
1403715913484058112
1403715913534057984
1403715913584058112
1403715913634057984
1403715913684058112
1403715913734057984
1403715913784058112
1403715913834057984
1403715913884058112
1403715913934057984
1403715913984058112
1403715914034057984
1403715914084058112
1403715914134057984
1403715914184058112
1403715914234057984
1403715914284058112
1403715914334057984
1403715914384058112
1403715914434057984
1403715914484058112
1403715914534057984
1403715914584058112
1403715914634057984
1403715914684058112
1403715914734057984
1403715914784058112
1403715914834057984
1403715914884058112
1403715914934057984
1403715914984058112
1403715915034057984
1403715915084058112
1403715915134057984
1403715915184058112
1403715915234057984
1403715915284058112
1403715915334057984
1403715915384058112
1403715915434057984
1403715915484058112
1403715915534057984
1403715915584058112
1403715915634057984
1403715915684058112
1403715915734057984
1403715915784058112
1403715915834057984
1403715915884058112
1403715915934057984
1403715915984058112
1403715916034057984
1403715916084058112
1403715916134057984
1403715916184058112
1403715916234057984
1403715916284058112
1403715916334057984
1403715916384058112
1403715916434057984
1403715916484058112
1403715916534057984
1403715916584058112
1403715916634057984
1403715916684058112
1403715916734057984
1403715916784058112
1403715916834057984
1403715916884058112
1403715916934057984
1403715916984058112
1403715917034057984
1403715917084058112
1403715917134057984
1403715917184058112
1403715917234057984
1403715917284058112
1403715917334057984
1403715917384058112
1403715917434057984
1403715917484058112
1403715917534057984
1403715917584058112
1403715917634057984
1403715917684058112
1403715917734057984
1403715917784058112
1403715917834057984
1403715917884058112
1403715917934057984
1403715917984058112
1403715918034057984
1403715918084058112
1403715918134057984
1403715918184058112
1403715918234057984
1403715918284058112
1403715918334057984
1403715918384058112
1403715918434057984
1403715918484058112
1403715918534057984
1403715918584058112
1403715918634057984
1403715918684058112
1403715918734057984
1403715918784058112
1403715918834057984
1403715918884058112
1403715918934057984
1403715918984058112
1403715919034057984
1403715919084058112
1403715919134057984
1403715919184058112
1403715919234057984
1403715919284058112
1403715919334057984
1403715919384058112
1403715919434057984
1403715919484058112
1403715919534057984
1403715919584058112
1403715919634057984
1403715919684058112
1403715919734057984
1403715919784058112
1403715919834057984
1403715919884058112
1403715919934057984
1403715919984058112
1403715920034057984
1403715920084058112
1403715920134057984
1403715920184058112
1403715920234057984
1403715920284058112
1403715920334057984
1403715920384058112
1403715920434057984
1403715920484058112
1403715920534057984
1403715920584058112
1403715920634057984
1403715920684058112
1403715920734057984
1403715920784058112
1403715920834057984
1403715920884058112
1403715920934057984
1403715920984058112
1403715921034057984
1403715921084058112
1403715921134057984
1403715921184058112
1403715921234057984
1403715921284058112
1403715921334057984
1403715921384058112
1403715921434057984
1403715921484058112
1403715921534057984
1403715921584058112
1403715921634057984
1403715921684058112
1403715921734057984
1403715921784058112
1403715921834057984
1403715921884058112
1403715921934057984
1403715921984058112
1403715922034057984
1403715922084058112
1403715922134057984
1403715922184058112
1403715922234057984
1403715922284058112
1403715922334057984
1403715922384058112
1403715922434057984
1403715922484058112
1403715922534057984
1403715922584058112
1403715922634057984
1403715922684058112
1403715922734057984
1403715922784058112
1403715922834057984
1403715922884058112
1403715922934057984
1403715922984058112
1403715923034057984
1403715923084058112
1403715923134057984
1403715923184058112
1403715923234057984
1403715923284058112
1403715923334057984
1403715923384058112
1403715923434057984
1403715923484058112
1403715923534057984
1403715923584058112
1403715923634057984
1403715923684058112
1403715923734057984
1403715923784058112
1403715923834057984
1403715923884058112
1403715923934057984
1403715923984058112
1403715924034057984
1403715924084058112
1403715924134057984
1403715924184058112
1403715924234057984
1403715924284058112
1403715924334057984
1403715924384058112
1403715924434057984
1403715924484058112
1403715924534057984
1403715924584058112
1403715924634057984
1403715924684058112
1403715924734057984
1403715924784058112
1403715924834057984
1403715924884058112
1403715924934057984
1403715924984058112
1403715925034057984
1403715925084058112
1403715925134057984
1403715925184058112
1403715925234057984
1403715925284058112
1403715925334057984
1403715925384058112
1403715925434057984
1403715925484058112
1403715925534057984
1403715925584058112
1403715925634057984
1403715925684058112
1403715925734057984
1403715925784058112
1403715925834057984
1403715925884058112
1403715925934057984
1403715925984058112
1403715926034057984
1403715926084058112
1403715926134057984
1403715926184058112
1403715926234057984
1403715926284058112
1403715926334057984
1403715926384058112
1403715926434057984
1403715926484058112
1403715926534057984
1403715926584058112
1403715926634057984
1403715926684058112
1403715926734057984
1403715926784058112
1403715926834057984
1403715926884058112
1403715926934057984
1403715926984058112
1403715927034057984
1403715927084058112
1403715927134057984
1403715927184058112
1403715927234057984
1403715927284058112
1403715927334057984
1403715927384058112
1403715927434057984
1403715927484058112
1403715927534057984
1403715927584058112
1403715927634057984
1403715927684058112
1403715927734057984
1403715927784058112
1403715927834057984
1403715927884058112
1403715927934057984
1403715927984058112
1403715928034057984
1403715928084058112
1403715928134057984
1403715928184058112
1403715928234057984
1403715928284058112
1403715928334057984
1403715928384058112
1403715928434057984
1403715928484058112
1403715928534057984
1403715928584058112
1403715928634057984
1403715928684058112
1403715928734057984
1403715928784058112
1403715928834057984
1403715928884058112
1403715928934057984
1403715928984058112
1403715929034057984
1403715929084058112
1403715929134057984
1403715929184058112
1403715929234057984
1403715929284058112
1403715929334057984
1403715929384058112
1403715929434057984
1403715929484058112
1403715929534057984
1403715929584058112
1403715929634057984
1403715929684058112
1403715929734057984
1403715929784058112
1403715929834057984
1403715929884058112
1403715929934057984
1403715929984058112
1403715930034057984
1403715930084058112
1403715930134057984
1403715930184058112
1403715930234057984
1403715930284058112
1403715930334057984
1403715930384058112
1403715930434057984
1403715930484058112
1403715930534057984
1403715930584058112
1403715930634057984
1403715930684058112
1403715930734057984
1403715930784058112
1403715930834057984
1403715930884058112
1403715930934057984
1403715930984058112
1403715931034057984
1403715931084058112
1403715931134057984
1403715931184058112
1403715931234057984
1403715931284058112
1403715931334057984
1403715931384058112
1403715931434057984
1403715931484058112
1403715931534057984
1403715931584058112
1403715931634057984
1403715931684058112
1403715931734057984
1403715931784058112
1403715931834057984
1403715931884058112
1403715931934057984
1403715931984058112
1403715932034057984
1403715932084058112
1403715932134057984
1403715932184058112
1403715932234057984
1403715932284058112
1403715932334057984
1403715932384058112
1403715932434057984
1403715932484058112
1403715932534057984
1403715932584058112
1403715932634057984
1403715932684058112
1403715932734057984
1403715932784058112
1403715932834057984
1403715932884058112
1403715932934057984
1403715932984058112
1403715933034057984
1403715933084058112
1403715933134057984
1403715933184058112
1403715933234057984
1403715933284058112
1403715933334057984
1403715933384058112
1403715933434057984
1403715933484058112
1403715933534057984
1403715933584058112
1403715933634057984
1403715933684058112
1403715933734057984
1403715933784058112
1403715933834057984
1403715933884058112
1403715933934057984
1403715933984058112
1403715934034057984
1403715934084058112
1403715934134057984
1403715934184058112
1403715934234057984
1403715934284058112
1403715934334057984
1403715934384058112
1403715934434057984
1403715934484058112
1403715934534057984
1403715934584058112
1403715934634057984
1403715934684058112
1403715934734057984
1403715934784058112
1403715934834057984
1403715934884058112
1403715934934057984
1403715934984058112
1403715935034057984
1403715935084058112
1403715935134057984
1403715935184058112
1403715935234057984
1403715935284058112
1403715935334057984
1403715935384058112
1403715935434057984
1403715935484058112
1403715935534057984
1403715935584058112
1403715935634057984
1403715935684058112
1403715935734057984
1403715935784058112
1403715935834057984
1403715935884058112
1403715935934057984
1403715935984058112
1403715936034057984
1403715936084058112
1403715936134057984
1403715936184058112
1403715936234057984
1403715936284058112
1403715936334057984
1403715936384058112
1403715936434057984
1403715936484058112
1403715936534057984
1403715936584058112
1403715936634057984
1403715936684058112
1403715936734057984
1403715936784058112
1403715936834057984
1403715936884058112
1403715936934057984
1403715936984058112
1403715937034057984
1403715937084058112
1403715937134057984
1403715937184058112
1403715937234057984
1403715937284058112
1403715937334057984
1403715937384058112
1403715937434057984
1403715937484058112
1403715937534057984
1403715937584058112
1403715937634057984
1403715937684058112
1403715937734057984
1403715937784058112
1403715937834057984
1403715937884058112
1403715937934057984
1403715937984058112
1403715938034057984
1403715938084058112
1403715938134057984
1403715938184058112
1403715938234057984
1403715938284058112
1403715938334057984
1403715938384058112
1403715938434057984
1403715938484058112
1403715938534057984
1403715938584058112
1403715938634057984
1403715938684058112
1403715938734057984
1403715938784058112
1403715938834057984
1403715938884058112
1403715938934057984
1403715938984058112
1403715939034057984
1403715939084058112
1403715939134057984
1403715939184058112
1403715939234057984
1403715939284058112
1403715939334057984
1403715939384058112
1403715939434057984
1403715939484058112
1403715939534057984
1403715939584058112
1403715939634057984
1403715939684058112
1403715939734057984
1403715939784058112
1403715939834057984
1403715939884058112
1403715939934057984
1403715939984058112
1403715940034057984
1403715940084058112
1403715940134057984
1403715940184058112
1403715940234057984
1403715940284058112
1403715940334057984
1403715940384058112
1403715940434057984
1403715940484058112
1403715940534057984
1403715940584058112
1403715940634057984
1403715940684058112
1403715940734057984
1403715940784058112
1403715940834057984
1403715940884058112
1403715940934057984
1403715940984058112
1403715941034057984
1403715941084058112
1403715941134057984
1403715941184058112
1403715941234057984
1403715941284058112
1403715941334057984
1403715941384058112
1403715941434057984
1403715941484058112
1403715941534057984
1403715941584058112
1403715941634057984
1403715941684058112
1403715941734057984
1403715941784058112
1403715941834057984
1403715941884058112
1403715941934057984
1403715941984058112
1403715942034057984
1403715942084058112
1403715942134057984
1403715942184058112
1403715942234057984
1403715942284058112
1403715942334057984
1403715942384058112
1403715942434057984
1403715942484058112
1403715942534057984
1403715942584058112
1403715942634057984
1403715942684058112
1403715942734057984
1403715942784058112
1403715942834057984
1403715942884058112
1403715942934057984
1403715942984058112
1403715943034057984
1403715943084058112
1403715943134057984
1403715943184058112
1403715943234057984
1403715943284058112
1403715943334057984
1403715943384058112
1403715943434057984
1403715943484058112
1403715943534057984
1403715943584058112
1403715943634057984
1403715943684058112
1403715943734057984
1403715943784058112
1403715943834057984
1403715943884058112
1403715943934057984
1403715943984058112
1403715944034057984
1403715944084058112
1403715944134057984
1403715944184058112
1403715944234057984
1403715944284058112
1403715944334057984
1403715944384058112
1403715944434057984
1403715944484058112
1403715944534057984
1403715944584058112
1403715944634057984
1403715944684058112
1403715944734057984
1403715944784058112
1403715944834057984
1403715944884058112
1403715944934057984
1403715944984058112
1403715945034057984
1403715945084058112
1403715945134057984
1403715945184058112
1403715945234057984
1403715945284058112
1403715945334057984
1403715945384058112
1403715945434057984
1403715945484058112
1403715945534057984
1403715945584058112
1403715945634057984
1403715945684058112
1403715945734057984
1403715945784058112
1403715945834057984
1403715945884058112
1403715945934057984
1403715945984058112
1403715946034057984
1403715946084058112
1403715946134057984
1403715946184058112
1403715946234057984
1403715946284058112
1403715946334057984
1403715946384058112
1403715946434057984
1403715946484058112
1403715946534057984
1403715946584058112
1403715946634057984
1403715946684058112
1403715946734057984
1403715946784058112
1403715946834057984
1403715946884058112
1403715946934057984
1403715946984058112
1403715947034057984
1403715947084058112
1403715947134057984
1403715947184058112
1403715947234057984
1403715947284058112
1403715947334057984
1403715947384058112
1403715947434057984
1403715947484058112
1403715947534057984
1403715947584058112
1403715947634057984
1403715947684058112
1403715947734057984
1403715947784058112
1403715947834057984
1403715947884058112
1403715947934057984
1403715947984058112
1403715948034057984
1403715948084058112
1403715948134057984
1403715948184058112
1403715948234057984
1403715948284058112
1403715948334057984
1403715948384058112
1403715948434057984
1403715948484058112
1403715948534057984
1403715948584058112
1403715948634057984
1403715948684058112
1403715948734057984
1403715948784058112
1403715948834057984
1403715948884058112
1403715948934057984
1403715948984058112
1403715949034057984
1403715949084058112
1403715949134057984
1403715949184058112
1403715949234057984
1403715949284058112
1403715949334057984
1403715949384058112
1403715949434057984
1403715949484058112
1403715949534057984
1403715949584058112
1403715949634057984
1403715949684058112
1403715949734057984
1403715949784058112
1403715949834057984
1403715949884058112
1403715949934057984
1403715949984058112
1403715950034057984
1403715950084058112
1403715950134057984
1403715950184058112
1403715950234057984
1403715950284058112
1403715950334057984
1403715950384058112
1403715950434057984
1403715950484058112
1403715950534057984
1403715950584058112
1403715950634057984
1403715950684058112
1403715950734057984
1403715950784058112
1403715950834057984
1403715950884058112
1403715950934057984
1403715950984058112
1403715951034057984
1403715951084058112
1403715951134057984
1403715951184058112
1403715951234057984
1403715951284058112
1403715951334057984
1403715951384058112
1403715951434057984
1403715951484058112
1403715951534057984
1403715951584058112
1403715951634057984
1403715951684058112
1403715951734057984
1403715951784058112
1403715951834057984
1403715951884058112
1403715951934057984
1403715951984058112
1403715952034057984
1403715952084058112
1403715952134057984
1403715952184058112
1403715952234057984
1403715952284058112
1403715952334057984
1403715952384058112
1403715952434057984
1403715952484058112
1403715952534057984
1403715952584058112
1403715952634057984
1403715952684058112
1403715952734057984
1403715952784058112
1403715952834057984
1403715952884058112
1403715952934057984
1403715952984058112
1403715953034057984
1403715953084058112
1403715953134057984
1403715953184058112
1403715953234057984
1403715953284058112
1403715953334057984
1403715953384058112
1403715953434057984
1403715953484058112
1403715953534057984
1403715953584058112
1403715953634057984
1403715953684058112
1403715953734057984
1403715953784058112
1403715953834057984
1403715953884058112
1403715953934057984
1403715953984058112
1403715954034057984
1403715954084058112
1403715954134057984
1403715954184058112
1403715954234057984
1403715954284058112
1403715954334057984
1403715954384058112
1403715954434057984
1403715954484058112
1403715954534057984
1403715954584058112
1403715954634057984
1403715954684058112
1403715954734057984
1403715954784058112
1403715954834057984
1403715954884058112
1403715954934057984
1403715954984058112
1403715955034057984
1403715955084058112
1403715955134057984
1403715955184058112
1403715955234057984
1403715955284058112
1403715955334057984
1403715955384058112
1403715955434057984
1403715955484058112
1403715955534057984
1403715955584058112
1403715955634057984
1403715955684058112
1403715955734057984
1403715955784058112
1403715955834057984
1403715955884058112
1403715955934057984
1403715955984058112
1403715956034057984
1403715956084058112
1403715956134057984
1403715956184058112
1403715956234057984
1403715956284058112
1403715956334057984
1403715956384058112
1403715956434057984
1403715956484058112
1403715956534057984
1403715956584058112
1403715956634057984
1403715956684058112
1403715956734057984
1403715956784058112
1403715956834057984
1403715956884058112
1403715956934057984
1403715956984058112
1403715957034057984
1403715957084058112
1403715957134057984
1403715957184058112
1403715957234057984
1403715957284058112
1403715957334057984
1403715957384058112
1403715957434057984
1403715957484058112
1403715957534057984
1403715957584058112
1403715957634057984
1403715957684058112
1403715957734057984
1403715957784058112
1403715957834057984
1403715957884058112
1403715957934057984
1403715957984058112
1403715958034057984
1403715958084058112
1403715958134057984
1403715958184058112
1403715958234057984
1403715958284058112
1403715958334057984
1403715958384058112
1403715958434057984
1403715958484058112
1403715958534057984
1403715958584058112
1403715958634057984
1403715958684058112
1403715958734057984
1403715958784058112
1403715958834057984
1403715958884058112
1403715958934057984
1403715958984058112
1403715959034057984
1403715959084058112
1403715959134057984
1403715959184058112
1403715959234057984
1403715959284058112
1403715959334057984
1403715959384058112
1403715959434057984
1403715959484058112
1403715959534057984
1403715959584058112
1403715959634057984
1403715959684058112
1403715959734057984
1403715959784058112
1403715959834057984
1403715959884058112
1403715959934057984
1403715959984058112
1403715960034057984
1403715960084058112
1403715960134057984
1403715960184058112
1403715960234057984
1403715960284058112
1403715960334057984
1403715960384058112
1403715960434057984
1403715960484058112
1403715960534057984
1403715960584058112
1403715960634057984
1403715960684058112
1403715960734057984
1403715960784058112
1403715960834057984
1403715960884058112
1403715960934057984
1403715960984058112
1403715961034057984
1403715961084058112
1403715961134057984
1403715961184058112
1403715961234057984
1403715961284058112
1403715961334057984
1403715961384058112
1403715961434057984
1403715961484058112
1403715961534057984
1403715961584058112
1403715961634057984
1403715961684058112
1403715961734057984
1403715961784058112
1403715961834057984
1403715961884058112
1403715961934057984
1403715961984058112
1403715962034057984
1403715962084058112
1403715962134057984
1403715962184058112
1403715962234057984
1403715962284058112
1403715962334057984
1403715962384058112
1403715962434057984
1403715962484058112
1403715962534057984
1403715962584058112
1403715962634057984
1403715962684058112
1403715962734057984
1403715962784058112
1403715962834057984
1403715962884058112
1403715962934057984
1403715962984058112
1403715963034057984
1403715963084058112
1403715963134057984
1403715963184058112
1403715963234057984
1403715963284058112
1403715963334057984
1403715963384058112
1403715963434057984
1403715963484058112
1403715963534057984
1403715963584058112
1403715963634057984
1403715963684058112
1403715963734057984
1403715963784058112
1403715963834057984
1403715963884058112
1403715963934057984
1403715963984058112
1403715964034057984
1403715964084058112
1403715964134057984
1403715964184058112
1403715964234057984
1403715964284058112
1403715964334057984
1403715964384058112
1403715964434057984
1403715964484058112
1403715964534057984
1403715964584058112
1403715964634057984
1403715964684058112
1403715964734057984
1403715964784058112
1403715964834057984
1403715964884058112
1403715964934057984
1403715964984058112
1403715965034057984
1403715965084058112
1403715965134057984
1403715965184058112
1403715965234057984
1403715965284058112
1403715965334057984
1403715965384058112
1403715965434057984
1403715965484058112
1403715965534057984
1403715965584058112
1403715965634057984
1403715965684058112
1403715965734057984
1403715965784058112
1403715965834057984
1403715965884058112
1403715965934057984
1403715965984058112
1403715966034057984
1403715966084058112
1403715966134057984
1403715966184058112
1403715966234057984
1403715966284058112
1403715966334057984
1403715966384058112
1403715966434057984
1403715966484058112
1403715966534057984
1403715966584058112
1403715966634057984
1403715966684058112
1403715966734057984
1403715966784058112
1403715966834057984
1403715966884058112
1403715966934057984
1403715966984058112
1403715967034057984
1403715967084058112
1403715967134057984
1403715967184058112
1403715967234057984
1403715967284058112
1403715967334057984
1403715967384058112
1403715967434057984
1403715967484058112
1403715967534057984
1403715967584058112
1403715967634057984
1403715967684058112
1403715967734057984
1403715967784058112
1403715967834057984
1403715967884058112
1403715967934057984
1403715967984058112
1403715968034057984
1403715968084058112
1403715968134057984
1403715968184058112
1403715968234057984
1403715968284058112
1403715968334057984
1403715968384058112
1403715968434057984
1403715968484058112
1403715968534057984
1403715968584058112
1403715968634057984
1403715968684058112
1403715968734057984
1403715968784058112
1403715968834057984
1403715968884058112
1403715968934057984
1403715968984058112
1403715969034057984
1403715969084058112
1403715969134057984
1403715969184058112
1403715969234057984
1403715969284058112
1403715969334057984
1403715969384058112
1403715969434057984
1403715969484058112
1403715969534057984
1403715969584058112
1403715969634057984
1403715969684058112
1403715969734057984
1403715969784058112
1403715969834057984
1403715969884058112
1403715969934057984
1403715969984058112
1403715970034057984
1403715970084058112
1403715970134057984
1403715970184058112
1403715970234057984
1403715970284058112
1403715970334057984
1403715970384058112
1403715970434057984
1403715970484058112
1403715970534057984
1403715970584058112
1403715970634057984
1403715970684058112
1403715970734057984
1403715970784058112
1403715970834057984
1403715970884058112
1403715970934057984
1403715970984058112
1403715971034057984
1403715971084058112
1403715971134057984
1403715971184058112
1403715971234057984
1403715971284058112
1403715971334057984
1403715971384058112
1403715971434057984
1403715971484058112
1403715971534057984
1403715971584058112
1403715971634057984
1403715971684058112
1403715971734057984
1403715971784058112
1403715971834057984
1403715971884058112
1403715971934057984
1403715971984058112
1403715972034057984
1403715972084058112
1403715972134057984
1403715972184058112
1403715972234057984
1403715972284058112
1403715972334057984
1403715972384058112
1403715972434057984
1403715972484058112
1403715972534057984
1403715972584058112
1403715972634057984
1403715972684058112
1403715972734057984
1403715972784058112
1403715972834057984
1403715972884058112
1403715972934057984
1403715972984058112
1403715973034057984
1403715973084058112
1403715973134057984
1403715973184058112
1403715973234057984
1403715973284058112
1403715973334057984
1403715973384058112
1403715973434057984
1403715973484058112
1403715973534057984
1403715973584058112
1403715973634057984
1403715973684058112
1403715973734057984
1403715973784058112
1403715973834057984
1403715973884058112
1403715973934057984
1403715973984058112
1403715974034057984
1403715974084058112
1403715974134057984
1403715974184058112
1403715974234057984
1403715974284058112
1403715974334057984
1403715974384058112
1403715974434057984
1403715974484058112
1403715974534057984
1403715974584058112
1403715974634057984
1403715974684058112
1403715974734057984
1403715974784058112
1403715974834057984
1403715974884058112
1403715974934057984
1403715974984058112
1403715975034057984
1403715975084058112
1403715975134057984
1403715975184058112
1403715975234057984
1403715975284058112
1403715975334057984
1403715975384058112
1403715975434057984
1403715975484058112
1403715975534057984
1403715975584058112
1403715975634057984
1403715975684058112
1403715975734057984
1403715975784058112
1403715975834057984
1403715975884058112
1403715975934057984
1403715975984058112
1403715976034057984
1403715976084058112
1403715976134057984
1403715976184058112
1403715976234057984
1403715976284058112
1403715976334057984
1403715976384058112
1403715976434057984
1403715976484058112
1403715976534057984
1403715976584058112
1403715976634057984
1403715976684058112
1403715976734057984
1403715976784058112
1403715976834057984
1403715976884058112
1403715976934057984
1403715976984058112
1403715977034057984
1403715977084058112
1403715977134057984
1403715977184058112
1403715977234057984
1403715977284058112
1403715977334057984
1403715977384058112
1403715977434057984
1403715977484058112
1403715977534057984
1403715977584058112
1403715977634057984
1403715977684058112
1403715977734057984
1403715977784058112
1403715977834057984
1403715977884058112
1403715977934057984
1403715977984058112
1403715978034057984
1403715978084058112
1403715978134057984
1403715978184058112
1403715978234057984
1403715978284058112
1403715978334057984
1403715978384058112
1403715978434057984
1403715978484058112
1403715978534057984
1403715978584058112
1403715978634057984
1403715978684058112
1403715978734057984
1403715978784058112
1403715978834057984
1403715978884058112
1403715978934057984
1403715978984058112
1403715979034057984
1403715979084058112
1403715979134057984
1403715979184058112
1403715979234057984
1403715979284058112
1403715979334057984
1403715979384058112
1403715979434057984
1403715979484058112
1403715979534057984
1403715979584058112
1403715979634057984
1403715979684058112
1403715979734057984
1403715979784058112
1403715979834057984
1403715979884058112
1403715979934057984
1403715979984058112
1403715980034057984
1403715980084058112
1403715980134057984
1403715980184058112
1403715980234057984
1403715980284058112
1403715980334057984
1403715980384058112
1403715980434057984
1403715980484058112
1403715980534057984
1403715980584058112
1403715980634057984
1403715980684058112
1403715980734057984
1403715980784058112
1403715980834057984
1403715980884058112
1403715980934057984
1403715980984058112
1403715981034057984
1403715981084058112
1403715981134057984
1403715981184058112
1403715981234057984
1403715981284058112
1403715981334057984
1403715981384058112
1403715981434057984
1403715981484058112
1403715981534057984
1403715981584058112
1403715981634057984
1403715981684058112
1403715981734057984
1403715981784058112
1403715981834057984
1403715981884058112
1403715981934057984
1403715981984058112
1403715982034057984
1403715982084058112
1403715982134057984
1403715982184058112
1403715982234057984
1403715982284058112
1403715982334057984
1403715982384058112
1403715982434057984
1403715982484058112
1403715982534057984
1403715982584058112
1403715982634057984
1403715982684058112
1403715982734057984
1403715982784058112
1403715982834057984
1403715982884058112
1403715982934057984
1403715982984058112
1403715983034057984
1403715983084058112
1403715983134057984
1403715983184058112
1403715983234057984
1403715983284058112
1403715983334057984
1403715983384058112
1403715983434057984
1403715983484058112
1403715983534057984
1403715983584058112
1403715983634057984
1403715983684058112
1403715983734057984
1403715983784058112
1403715983834057984
1403715983884058112
1403715983934057984
1403715983984058112
1403715984034057984
1403715984084058112
1403715984134057984
1403715984184058112
1403715984234057984
1403715984284058112
1403715984334057984
1403715984384058112
1403715984434057984
1403715984484058112
1403715984534057984
1403715984584058112
1403715984634057984
1403715984684058112
1403715984734057984
1403715984784058112
1403715984834057984
1403715984884058112
1403715984934057984
1403715984984058112
1403715985034057984
1403715985084058112
1403715985134057984
1403715985184058112
1403715985234057984
1403715985284058112
1403715985334057984
1403715985384058112
1403715985434057984
1403715985484058112
1403715985534057984
1403715985584058112
1403715985634057984
1403715985684058112
1403715985734057984
1403715985784058112
1403715985834057984
1403715985884058112
1403715985934057984
1403715985984058112
1403715986034057984
1403715986084058112
1403715986134057984
1403715986184058112
1403715986234057984
1403715986284058112
1403715986334057984
1403715986384058112
1403715986434057984
1403715986484058112
1403715986534057984
1403715986584058112
1403715986634057984
1403715986684058112
1403715986734057984
1403715986784058112
1403715986834057984
1403715986884058112
1403715986934057984
1403715986984058112
1403715987034057984
1403715987084058112
1403715987134057984
1403715987184058112
1403715987234057984
1403715987284058112
1403715987334057984
1403715987384058112
1403715987434057984
1403715987484058112
1403715987534057984
1403715987584058112
1403715987634057984
1403715987684058112
1403715987734057984
1403715987784058112
1403715987834057984
1403715987884058112
1403715987934057984
1403715987984058112
1403715988034057984
1403715988084058112
1403715988134057984
1403715988184058112
1403715988234057984
1403715988284058112
1403715988334057984
1403715988384058112
1403715988434057984
1403715988484058112
1403715988534057984
1403715988584058112
1403715988634057984
1403715988684058112
1403715988734057984
1403715988784058112
1403715988834057984
1403715988884058112
1403715988934057984
1403715988984058112
1403715989034057984
1403715989084058112
1403715989134057984
1403715989184058112
1403715989234057984
1403715989284058112
1403715989334057984
1403715989384058112
1403715989434057984
1403715989484058112
1403715989534057984
1403715989584058112
1403715989634057984
1403715989684058112
1403715989734057984
1403715989784058112
1403715989834057984
1403715989884058112
1403715989934057984
1403715989984058112
1403715990034057984
1403715990084058112
1403715990134057984
1403715990184058112
1403715990234057984
1403715990284058112
1403715990334057984
1403715990384058112
1403715990434057984
1403715990484058112
1403715990534057984
1403715990584058112
1403715990634057984
1403715990684058112
1403715990734057984
1403715990784058112
1403715990834057984
1403715990884058112
1403715990934057984
1403715990984058112
1403715991034057984
1403715991084058112
1403715991134057984
1403715991184058112
1403715991234057984
1403715991284058112
1403715991334057984
1403715991384058112
1403715991434057984
1403715991484058112
1403715991534057984
1403715991584058112
1403715991634057984
1403715991684058112
1403715991734057984
1403715991784058112
1403715991834057984
1403715991884058112
1403715991934057984
1403715991984058112
1403715992034057984
1403715992084058112
1403715992134057984
1403715992184058112
1403715992234057984
1403715992284058112
1403715992334057984
1403715992384058112
1403715992434057984
1403715992484058112
1403715992534057984
1403715992584058112
1403715992634057984
1403715992684058112
1403715992734057984
1403715992784058112
1403715992834057984
1403715992884058112
1403715992934057984
1403715992984058112
1403715993034057984
1403715993084058112
1403715993134057984
1403715993184058112
1403715993234057984
1403715993284058112
1403715993334057984
1403715993384058112
1403715993434057984
1403715993484058112
1403715993534057984
1403715993584058112
1403715993634057984
1403715993684058112
1403715993734057984
1403715993784058112
1403715993834057984
1403715993884058112
1403715993934057984
1403715993984058112
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/V201.txt
================================================
1413393212255760384
1413393212305760512
1413393212355760384
1413393212405760512
1413393212455760384
1413393212505760512
1413393212555760384
1413393212605760512
1413393212655760384
1413393212705760512
1413393212755760384
1413393212805760512
1413393212855760384
1413393212905760512
1413393212955760384
1413393213005760512
1413393213055760384
1413393213105760512
1413393213155760384
1413393213205760512
1413393213255760384
1413393213305760512
1413393213355760384
1413393213405760512
1413393213455760384
1413393213505760512
1413393213555760384
1413393213605760512
1413393213655760384
1413393213705760512
1413393213755760384
1413393213805760512
1413393213855760384
1413393213905760512
1413393213955760384
1413393214005760512
1413393214055760384
1413393214105760512
1413393214155760384
1413393214205760512
1413393214255760384
1413393214305760512
1413393214355760384
1413393214405760512
1413393214455760384
1413393214505760512
1413393214555760384
1413393214605760512
1413393214655760384
1413393214705760512
1413393214755760384
1413393214805760512
1413393214855760384
1413393214905760512
1413393214955760384
1413393215005760512
1413393215055760384
1413393215105760512
1413393215155760384
1413393215205760512
1413393215255760384
1413393215305760512
1413393215355760384
1413393215405760512
1413393215455760384
1413393215505760512
1413393215555760384
1413393215605760512
1413393215655760384
1413393215705760512
1413393215755760384
1413393215805760512
1413393215855760384
1413393215905760512
1413393215955760384
1413393216005760512
1413393216055760384
1413393216105760512
1413393216155760384
1413393216205760512
1413393216255760384
1413393216305760512
1413393216355760384
1413393216405760512
1413393216455760384
1413393216505760512
1413393216555760384
1413393216605760512
1413393216655760384
1413393216705760512
1413393216755760384
1413393216805760512
1413393216855760384
1413393216905760512
1413393216955760384
1413393217005760512
1413393217055760384
1413393217105760512
1413393217155760384
1413393217205760512
1413393217255760384
1413393217305760512
1413393217355760384
1413393217405760512
1413393217455760384
1413393217505760512
1413393217555760384
1413393217605760512
1413393217655760384
1413393217705760512
1413393217755760384
1413393217805760512
1413393217855760384
1413393217905760512
1413393217955760384
1413393218005760512
1413393218055760384
1413393218105760512
1413393218155760384
1413393218205760512
1413393218255760384
1413393218305760512
1413393218355760384
1413393218405760512
1413393218455760384
1413393218505760512
1413393218555760384
1413393218605760512
1413393218655760384
1413393218705760512
1413393218755760384
1413393218805760512
1413393218855760384
1413393218905760512
1413393218955760384
1413393219005760512
1413393219055760384
1413393219105760512
1413393219155760384
1413393219205760512
1413393219255760384
1413393219305760512
1413393219355760384
1413393219405760512
1413393219455760384
1413393219505760512
1413393219555760384
1413393219605760512
1413393219655760384
1413393219705760512
1413393219755760384
1413393219805760512
1413393219855760384
1413393219905760512
1413393219955760384
1413393220005760512
1413393220055760384
1413393220105760512
1413393220155760384
1413393220205760512
1413393220255760384
1413393220305760512
1413393220355760384
1413393220405760512
1413393220455760384
1413393220505760512
1413393220555760384
1413393220605760512
1413393220655760384
1413393220705760512
1413393220755760384
1413393220805760512
1413393220855760384
1413393220905760512
1413393220955760384
1413393221005760512
1413393221055760384
1413393221105760512
1413393221155760384
1413393221205760512
1413393221255760384
1413393221305760512
1413393221355760384
1413393221405760512
1413393221455760384
1413393221505760512
1413393221555760384
1413393221605760512
1413393221655760384
1413393221705760512
1413393221755760384
1413393221805760512
1413393221855760384
1413393221905760512
1413393221955760384
1413393222005760512
1413393222055760384
1413393222105760512
1413393222155760384
1413393222205760512
1413393222255760384
1413393222305760512
1413393222355760384
1413393222405760512
1413393222455760384
1413393222505760512
1413393222555760384
1413393222605760512
1413393222655760384
1413393222705760512
1413393222755760384
1413393222805760512
1413393222855760384
1413393222905760512
1413393222955760384
1413393223005760512
1413393223055760384
1413393223105760512
1413393223155760384
1413393223205760512
1413393223255760384
1413393223305760512
1413393223355760384
1413393223405760512
1413393223455760384
1413393223505760512
1413393223555760384
1413393223605760512
1413393223655760384
1413393223705760512
1413393223755760384
1413393223805760512
1413393223855760384
1413393223905760512
1413393223955760384
1413393224005760512
1413393224055760384
1413393224105760512
1413393224155760384
1413393224205760512
1413393224255760384
1413393224305760512
1413393224355760384
1413393224405760512
1413393224455760384
1413393224505760512
1413393224555760384
1413393224605760512
1413393224655760384
1413393224705760512
1413393224755760384
1413393224805760512
1413393224855760384
1413393224905760512
1413393224955760384
1413393225005760512
1413393225055760384
1413393225105760512
1413393225155760384
1413393225205760512
1413393225255760384
1413393225305760512
1413393225355760384
1413393225405760512
1413393225455760384
1413393225505760512
1413393225555760384
1413393225605760512
1413393225655760384
1413393225705760512
1413393225755760384
1413393225805760512
1413393225855760384
1413393225905760512
1413393225955760384
1413393226005760512
1413393226055760384
1413393226105760512
1413393226155760384
1413393226205760512
1413393226255760384
1413393226305760512
1413393226355760384
1413393226405760512
1413393226455760384
1413393226505760512
1413393226555760384
1413393226605760512
1413393226655760384
1413393226705760512
1413393226755760384
1413393226805760512
1413393226855760384
1413393226905760512
1413393226955760384
1413393227005760512
1413393227055760384
1413393227105760512
1413393227155760384
1413393227205760512
1413393227255760384
1413393227305760512
1413393227355760384
1413393227405760512
1413393227455760384
1413393227505760512
1413393227555760384
1413393227605760512
1413393227655760384
1413393227705760512
1413393227755760384
1413393227805760512
1413393227855760384
1413393227905760512
1413393227955760384
1413393228005760512
1413393228055760384
1413393228105760512
1413393228155760384
1413393228205760512
1413393228255760384
1413393228305760512
1413393228355760384
1413393228405760512
1413393228455760384
1413393228505760512
1413393228555760384
1413393228605760512
1413393228655760384
1413393228705760512
1413393228755760384
1413393228805760512
1413393228855760384
1413393228905760512
1413393228955760384
1413393229005760512
1413393229055760384
1413393229105760512
1413393229155760384
1413393229205760512
1413393229255760384
1413393229305760512
1413393229355760384
1413393229405760512
1413393229455760384
1413393229505760512
1413393229555760384
1413393229605760512
1413393229655760384
1413393229705760512
1413393229755760384
1413393229805760512
1413393229855760384
1413393229905760512
1413393229955760384
1413393230005760512
1413393230055760384
1413393230105760512
1413393230155760384
1413393230205760512
1413393230255760384
1413393230305760512
1413393230355760384
1413393230405760512
1413393230455760384
1413393230505760512
1413393230555760384
1413393230605760512
1413393230655760384
1413393230705760512
1413393230755760384
1413393230805760512
1413393230855760384
1413393230905760512
1413393230955760384
1413393231005760512
1413393231055760384
1413393231105760512
1413393231155760384
1413393231205760512
1413393231255760384
1413393231305760512
1413393231355760384
1413393231405760512
1413393231455760384
1413393231505760512
1413393231555760384
1413393231605760512
1413393231655760384
1413393231705760512
1413393231755760384
1413393231805760512
1413393231855760384
1413393231905760512
1413393231955760384
1413393232005760512
1413393232055760384
1413393232105760512
1413393232155760384
1413393232205760512
1413393232255760384
1413393232305760512
1413393232355760384
1413393232405760512
1413393232455760384
1413393232505760512
1413393232555760384
1413393232605760512
1413393232655760384
1413393232705760512
1413393232755760384
1413393232805760512
1413393232855760384
1413393232905760512
1413393232955760384
1413393233005760512
1413393233055760384
1413393233105760512
1413393233155760384
1413393233205760512
1413393233255760384
1413393233305760512
1413393233355760384
1413393233405760512
1413393233455760384
1413393233505760512
1413393233555760384
1413393233605760512
1413393233655760384
1413393233705760512
1413393233755760384
1413393233805760512
1413393233855760384
1413393233905760512
1413393233955760384
1413393234005760512
1413393234055760384
1413393234105760512
1413393234155760384
1413393234205760512
1413393234255760384
1413393234305760512
1413393234355760384
1413393234405760512
1413393234455760384
1413393234505760512
1413393234555760384
1413393234605760512
1413393234655760384
1413393234705760512
1413393234755760384
1413393234805760512
1413393234855760384
1413393234905760512
1413393234955760384
1413393235005760512
1413393235055760384
1413393235105760512
1413393235155760384
1413393235205760512
1413393235255760384
1413393235305760512
1413393235355760384
1413393235405760512
1413393235455760384
1413393235505760512
1413393235555760384
1413393235605760512
1413393235655760384
1413393235705760512
1413393235755760384
1413393235805760512
1413393235855760384
1413393235905760512
1413393235955760384
1413393236005760512
1413393236055760384
1413393236105760512
1413393236155760384
1413393236205760512
1413393236255760384
1413393236305760512
1413393236355760384
1413393236405760512
1413393236455760384
1413393236505760512
1413393236555760384
1413393236605760512
1413393236655760384
1413393236705760512
1413393236755760384
1413393236805760512
1413393236855760384
1413393236905760512
1413393236955760384
1413393237005760512
1413393237055760384
1413393237105760512
1413393237155760384
1413393237205760512
1413393237255760384
1413393237305760512
1413393237355760384
1413393237405760512
1413393237455760384
1413393237505760512
1413393237555760384
1413393237605760512
1413393237655760384
1413393237705760512
1413393237755760384
1413393237805760512
1413393237855760384
1413393237905760512
1413393237955760384
1413393238005760512
1413393238055760384
1413393238105760512
1413393238155760384
1413393238205760512
1413393238255760384
1413393238305760512
1413393238355760384
1413393238405760512
1413393238455760384
1413393238505760512
1413393238555760384
1413393238605760512
1413393238655760384
1413393238705760512
1413393238755760384
1413393238805760512
1413393238855760384
1413393238905760512
1413393238955760384
1413393239005760512
1413393239055760384
1413393239105760512
1413393239155760384
1413393239205760512
1413393239255760384
1413393239305760512
1413393239355760384
1413393239405760512
1413393239455760384
1413393239505760512
1413393239555760384
1413393239605760512
1413393239655760384
1413393239705760512
1413393239755760384
1413393239805760512
1413393239855760384
1413393239905760512
1413393239955760384
1413393240005760512
1413393240055760384
1413393240105760512
1413393240155760384
1413393240205760512
1413393240255760384
1413393240305760512
1413393240355760384
1413393240405760512
1413393240455760384
1413393240505760512
1413393240555760384
1413393240605760512
1413393240655760384
1413393240705760512
1413393240755760384
1413393240805760512
1413393240855760384
1413393240905760512
1413393240955760384
1413393241005760512
1413393241055760384
1413393241105760512
1413393241155760384
1413393241205760512
1413393241255760384
1413393241305760512
1413393241355760384
1413393241405760512
1413393241455760384
1413393241505760512
1413393241555760384
1413393241605760512
1413393241655760384
1413393241705760512
1413393241755760384
1413393241805760512
1413393241855760384
1413393241905760512
1413393241955760384
1413393242005760512
1413393242055760384
1413393242105760512
1413393242155760384
1413393242205760512
1413393242255760384
1413393242305760512
1413393242355760384
1413393242405760512
1413393242455760384
1413393242505760512
1413393242555760384
1413393242605760512
1413393242655760384
1413393242705760512
1413393242755760384
1413393242805760512
1413393242855760384
1413393242905760512
1413393242955760384
1413393243005760512
1413393243055760384
1413393243105760512
1413393243155760384
1413393243205760512
1413393243255760384
1413393243305760512
1413393243355760384
1413393243405760512
1413393243455760384
1413393243505760512
1413393243555760384
1413393243605760512
1413393243655760384
1413393243705760512
1413393243755760384
1413393243805760512
1413393243855760384
1413393243905760512
1413393243955760384
1413393244005760512
1413393244055760384
1413393244105760512
1413393244155760384
1413393244205760512
1413393244255760384
1413393244305760512
1413393244355760384
1413393244405760512
1413393244455760384
1413393244505760512
1413393244555760384
1413393244605760512
1413393244655760384
1413393244705760512
1413393244755760384
1413393244805760512
1413393244855760384
1413393244905760512
1413393244955760384
1413393245005760512
1413393245055760384
1413393245105760512
1413393245155760384
1413393245205760512
1413393245255760384
1413393245305760512
1413393245355760384
1413393245405760512
1413393245455760384
1413393245505760512
1413393245555760384
1413393245605760512
1413393245655760384
1413393245705760512
1413393245755760384
1413393245805760512
1413393245855760384
1413393245905760512
1413393245955760384
1413393246005760512
1413393246055760384
1413393246105760512
1413393246155760384
1413393246205760512
1413393246255760384
1413393246305760512
1413393246355760384
1413393246405760512
1413393246455760384
1413393246505760512
1413393246555760384
1413393246605760512
1413393246655760384
1413393246705760512
1413393246755760384
1413393246805760512
1413393246855760384
1413393246905760512
1413393246955760384
1413393247005760512
1413393247055760384
1413393247105760512
1413393247155760384
1413393247205760512
1413393247255760384
1413393247305760512
1413393247355760384
1413393247405760512
1413393247455760384
1413393247505760512
1413393247555760384
1413393247605760512
1413393247655760384
1413393247705760512
1413393247755760384
1413393247805760512
1413393247855760384
1413393247905760512
1413393247955760384
1413393248005760512
1413393248055760384
1413393248105760512
1413393248155760384
1413393248205760512
1413393248255760384
1413393248305760512
1413393248355760384
1413393248405760512
1413393248455760384
1413393248505760512
1413393248555760384
1413393248605760512
1413393248655760384
1413393248705760512
1413393248755760384
1413393248805760512
1413393248855760384
1413393248905760512
1413393248955760384
1413393249005760512
1413393249055760384
1413393249105760512
1413393249155760384
1413393249205760512
1413393249255760384
1413393249305760512
1413393249355760384
1413393249405760512
1413393249455760384
1413393249505760512
1413393249555760384
1413393249605760512
1413393249655760384
1413393249705760512
1413393249755760384
1413393249805760512
1413393249855760384
1413393249905760512
1413393249955760384
1413393250005760512
1413393250055760384
1413393250105760512
1413393250155760384
1413393250205760512
1413393250255760384
1413393250305760512
1413393250355760384
1413393250405760512
1413393250455760384
1413393250505760512
1413393250555760384
1413393250605760512
1413393250655760384
1413393250705760512
1413393250755760384
1413393250805760512
1413393250855760384
1413393250905760512
1413393250955760384
1413393251005760512
1413393251055760384
1413393251105760512
1413393251155760384
1413393251205760512
1413393251255760384
1413393251305760512
1413393251355760384
1413393251405760512
1413393251455760384
1413393251505760512
1413393251555760384
1413393251605760512
1413393251655760384
1413393251705760512
1413393251755760384
1413393251805760512
1413393251855760384
1413393251905760512
1413393251955760384
1413393252005760512
1413393252055760384
1413393252105760512
1413393252155760384
1413393252205760512
1413393252255760384
1413393252305760512
1413393252355760384
1413393252405760512
1413393252455760384
1413393252505760512
1413393252555760384
1413393252605760512
1413393252655760384
1413393252705760512
1413393252755760384
1413393252805760512
1413393252855760384
1413393252905760512
1413393252955760384
1413393253005760512
1413393253055760384
1413393253105760512
1413393253155760384
1413393253205760512
1413393253255760384
1413393253305760512
1413393253355760384
1413393253405760512
1413393253455760384
1413393253505760512
1413393253555760384
1413393253605760512
1413393253655760384
1413393253705760512
1413393253755760384
1413393253805760512
1413393253855760384
1413393253905760512
1413393253955760384
1413393254005760512
1413393254055760384
1413393254105760512
1413393254155760384
1413393254205760512
1413393254255760384
1413393254305760512
1413393254355760384
1413393254405760512
1413393254455760384
1413393254505760512
1413393254555760384
1413393254605760512
1413393254655760384
1413393254705760512
1413393254755760384
1413393254805760512
1413393254855760384
1413393254905760512
1413393254955760384
1413393255005760512
1413393255055760384
1413393255105760512
1413393255155760384
1413393255205760512
1413393255255760384
1413393255305760512
1413393255355760384
1413393255405760512
1413393255455760384
1413393255505760512
1413393255555760384
1413393255605760512
1413393255655760384
1413393255705760512
1413393255755760384
1413393255805760512
1413393255855760384
1413393255905760512
1413393255955760384
1413393256005760512
1413393256055760384
1413393256105760512
1413393256155760384
1413393256205760512
1413393256255760384
1413393256305760512
1413393256355760384
1413393256405760512
1413393256455760384
1413393256505760512
1413393256555760384
1413393256605760512
1413393256655760384
1413393256705760512
1413393256755760384
1413393256805760512
1413393256855760384
1413393256905760512
1413393256955760384
1413393257005760512
1413393257055760384
1413393257105760512
1413393257155760384
1413393257205760512
1413393257255760384
1413393257305760512
1413393257355760384
1413393257405760512
1413393257455760384
1413393257505760512
1413393257555760384
1413393257605760512
1413393257655760384
1413393257705760512
1413393257755760384
1413393257805760512
1413393257855760384
1413393257905760512
1413393257955760384
1413393258005760512
1413393258055760384
1413393258105760512
1413393258155760384
1413393258205760512
1413393258255760384
1413393258305760512
1413393258355760384
1413393258405760512
1413393258455760384
1413393258505760512
1413393258555760384
1413393258605760512
1413393258655760384
1413393258705760512
1413393258755760384
1413393258805760512
1413393258855760384
1413393258905760512
1413393258955760384
1413393259005760512
1413393259055760384
1413393259105760512
1413393259155760384
1413393259205760512
1413393259255760384
1413393259305760512
1413393259355760384
1413393259405760512
1413393259455760384
1413393259505760512
1413393259555760384
1413393259605760512
1413393259655760384
1413393259705760512
1413393259755760384
1413393259805760512
1413393259855760384
1413393259905760512
1413393259955760384
1413393260005760512
1413393260055760384
1413393260105760512
1413393260155760384
1413393260205760512
1413393260255760384
1413393260305760512
1413393260355760384
1413393260405760512
1413393260455760384
1413393260505760512
1413393260555760384
1413393260605760512
1413393260655760384
1413393260705760512
1413393260755760384
1413393260805760512
1413393260855760384
1413393260905760512
1413393260955760384
1413393261005760512
1413393261055760384
1413393261105760512
1413393261155760384
1413393261205760512
1413393261255760384
1413393261305760512
1413393261355760384
1413393261405760512
1413393261455760384
1413393261505760512
1413393261555760384
1413393261605760512
1413393261655760384
1413393261705760512
1413393261755760384
1413393261805760512
1413393261855760384
1413393261905760512
1413393261955760384
1413393262005760512
1413393262055760384
1413393262105760512
1413393262155760384
1413393262205760512
1413393262255760384
1413393262305760512
1413393262355760384
1413393262405760512
1413393262455760384
1413393262505760512
1413393262555760384
1413393262605760512
1413393262655760384
1413393262705760512
1413393262755760384
1413393262805760512
1413393262855760384
1413393262905760512
1413393262955760384
1413393263005760512
1413393263055760384
1413393263105760512
1413393263155760384
1413393263205760512
1413393263255760384
1413393263305760512
1413393263355760384
1413393263405760512
1413393263455760384
1413393263505760512
1413393263555760384
1413393263605760512
1413393263655760384
1413393263705760512
1413393263755760384
1413393263805760512
1413393263855760384
1413393263905760512
1413393263955760384
1413393264005760512
1413393264055760384
1413393264105760512
1413393264155760384
1413393264205760512
1413393264255760384
1413393264305760512
1413393264355760384
1413393264405760512
1413393264455760384
1413393264505760512
1413393264555760384
1413393264605760512
1413393264655760384
1413393264705760512
1413393264755760384
1413393264805760512
1413393264855760384
1413393264905760512
1413393264955760384
1413393265005760512
1413393265055760384
1413393265105760512
1413393265155760384
1413393265205760512
1413393265255760384
1413393265305760512
1413393265355760384
1413393265405760512
1413393265455760384
1413393265505760512
1413393265555760384
1413393265605760512
1413393265655760384
1413393265705760512
1413393265755760384
1413393265805760512
1413393265855760384
1413393265905760512
1413393265955760384
1413393266005760512
1413393266055760384
1413393266105760512
1413393266155760384
1413393266205760512
1413393266255760384
1413393266305760512
1413393266355760384
1413393266405760512
1413393266455760384
1413393266505760512
1413393266555760384
1413393266605760512
1413393266655760384
1413393266705760512
1413393266755760384
1413393266805760512
1413393266855760384
1413393266905760512
1413393266955760384
1413393267005760512
1413393267055760384
1413393267105760512
1413393267155760384
1413393267205760512
1413393267255760384
1413393267305760512
1413393267355760384
1413393267405760512
1413393267455760384
1413393267505760512
1413393267555760384
1413393267605760512
1413393267655760384
1413393267705760512
1413393267755760384
1413393267805760512
1413393267855760384
1413393267905760512
1413393267955760384
1413393268005760512
1413393268055760384
1413393268105760512
1413393268155760384
1413393268205760512
1413393268255760384
1413393268305760512
1413393268355760384
1413393268405760512
1413393268455760384
1413393268505760512
1413393268555760384
1413393268605760512
1413393268655760384
1413393268705760512
1413393268755760384
1413393268805760512
1413393268855760384
1413393268905760512
1413393268955760384
1413393269005760512
1413393269055760384
1413393269105760512
1413393269155760384
1413393269205760512
1413393269255760384
1413393269305760512
1413393269355760384
1413393269405760512
1413393269455760384
1413393269505760512
1413393269555760384
1413393269605760512
1413393269655760384
1413393269705760512
1413393269755760384
1413393269805760512
1413393269855760384
1413393269905760512
1413393269955760384
1413393270005760512
1413393270055760384
1413393270105760512
1413393270155760384
1413393270205760512
1413393270255760384
1413393270305760512
1413393270355760384
1413393270405760512
1413393270455760384
1413393270505760512
1413393270555760384
1413393270605760512
1413393270655760384
1413393270705760512
1413393270755760384
1413393270805760512
1413393270855760384
1413393270905760512
1413393270955760384
1413393271005760512
1413393271055760384
1413393271105760512
1413393271155760384
1413393271205760512
1413393271255760384
1413393271305760512
1413393271355760384
1413393271405760512
1413393271455760384
1413393271505760512
1413393271555760384
1413393271605760512
1413393271655760384
1413393271705760512
1413393271755760384
1413393271805760512
1413393271855760384
1413393271905760512
1413393271955760384
1413393272005760512
1413393272055760384
1413393272105760512
1413393272155760384
1413393272205760512
1413393272255760384
1413393272305760512
1413393272355760384
1413393272405760512
1413393272455760384
1413393272505760512
1413393272555760384
1413393272605760512
1413393272655760384
1413393272705760512
1413393272755760384
1413393272805760512
1413393272855760384
1413393272905760512
1413393272955760384
1413393273005760512
1413393273055760384
1413393273105760512
1413393273155760384
1413393273205760512
1413393273255760384
1413393273305760512
1413393273355760384
1413393273405760512
1413393273455760384
1413393273505760512
1413393273555760384
1413393273605760512
1413393273655760384
1413393273705760512
1413393273755760384
1413393273805760512
1413393273855760384
1413393273905760512
1413393273955760384
1413393274005760512
1413393274055760384
1413393274105760512
1413393274155760384
1413393274205760512
1413393274255760384
1413393274305760512
1413393274355760384
1413393274405760512
1413393274455760384
1413393274505760512
1413393274555760384
1413393274605760512
1413393274655760384
1413393274705760512
1413393274755760384
1413393274805760512
1413393274855760384
1413393274905760512
1413393274955760384
1413393275005760512
1413393275055760384
1413393275105760512
1413393275155760384
1413393275205760512
1413393275255760384
1413393275305760512
1413393275355760384
1413393275405760512
1413393275455760384
1413393275505760512
1413393275555760384
1413393275605760512
1413393275655760384
1413393275705760512
1413393275755760384
1413393275805760512
1413393275855760384
1413393275905760512
1413393275955760384
1413393276005760512
1413393276055760384
1413393276105760512
1413393276155760384
1413393276205760512
1413393276255760384
1413393276305760512
1413393276355760384
1413393276405760512
1413393276455760384
1413393276505760512
1413393276555760384
1413393276605760512
1413393276655760384
1413393276705760512
1413393276755760384
1413393276805760512
1413393276855760384
1413393276905760512
1413393276955760384
1413393277005760512
1413393277055760384
1413393277105760512
1413393277155760384
1413393277205760512
1413393277255760384
1413393277305760512
1413393277355760384
1413393277405760512
1413393277455760384
1413393277505760512
1413393277555760384
1413393277605760512
1413393277655760384
1413393277705760512
1413393277755760384
1413393277805760512
1413393277855760384
1413393277905760512
1413393277955760384
1413393278005760512
1413393278055760384
1413393278105760512
1413393278155760384
1413393278205760512
1413393278255760384
1413393278305760512
1413393278355760384
1413393278405760512
1413393278455760384
1413393278505760512
1413393278555760384
1413393278605760512
1413393278655760384
1413393278705760512
1413393278755760384
1413393278805760512
1413393278855760384
1413393278905760512
1413393278955760384
1413393279005760512
1413393279055760384
1413393279105760512
1413393279155760384
1413393279205760512
1413393279255760384
1413393279305760512
1413393279355760384
1413393279405760512
1413393279455760384
1413393279505760512
1413393279555760384
1413393279605760512
1413393279655760384
1413393279705760512
1413393279755760384
1413393279805760512
1413393279855760384
1413393279905760512
1413393279955760384
1413393280005760512
1413393280055760384
1413393280105760512
1413393280155760384
1413393280205760512
1413393280255760384
1413393280305760512
1413393280355760384
1413393280405760512
1413393280455760384
1413393280505760512
1413393280555760384
1413393280605760512
1413393280655760384
1413393280705760512
1413393280755760384
1413393280805760512
1413393280855760384
1413393280905760512
1413393280955760384
1413393281005760512
1413393281055760384
1413393281105760512
1413393281155760384
1413393281205760512
1413393281255760384
1413393281305760512
1413393281355760384
1413393281405760512
1413393281455760384
1413393281505760512
1413393281555760384
1413393281605760512
1413393281655760384
1413393281705760512
1413393281755760384
1413393281805760512
1413393281855760384
1413393281905760512
1413393281955760384
1413393282005760512
1413393282055760384
1413393282105760512
1413393282155760384
1413393282205760512
1413393282255760384
1413393282305760512
1413393282355760384
1413393282405760512
1413393282455760384
1413393282505760512
1413393282555760384
1413393282605760512
1413393282655760384
1413393282705760512
1413393282755760384
1413393282805760512
1413393282855760384
1413393282905760512
1413393282955760384
1413393283005760512
1413393283055760384
1413393283105760512
1413393283155760384
1413393283205760512
1413393283255760384
1413393283305760512
1413393283355760384
1413393283405760512
1413393283455760384
1413393283505760512
1413393283555760384
1413393283605760512
1413393283655760384
1413393283705760512
1413393283755760384
1413393283805760512
1413393283855760384
1413393283905760512
1413393283955760384
1413393284005760512
1413393284055760384
1413393284105760512
1413393284155760384
1413393284205760512
1413393284255760384
1413393284305760512
1413393284355760384
1413393284405760512
1413393284455760384
1413393284505760512
1413393284555760384
1413393284605760512
1413393284655760384
1413393284705760512
1413393284755760384
1413393284805760512
1413393284855760384
1413393284905760512
1413393284955760384
1413393285005760512
1413393285055760384
1413393285105760512
1413393285155760384
1413393285205760512
1413393285255760384
1413393285305760512
1413393285355760384
1413393285405760512
1413393285455760384
1413393285505760512
1413393285555760384
1413393285605760512
1413393285655760384
1413393285705760512
1413393285755760384
1413393285805760512
1413393285855760384
1413393285905760512
1413393285955760384
1413393286005760512
1413393286055760384
1413393286105760512
1413393286155760384
1413393286205760512
1413393286255760384
1413393286305760512
1413393286355760384
1413393286405760512
1413393286455760384
1413393286505760512
1413393286555760384
1413393286605760512
1413393286655760384
1413393286705760512
1413393286755760384
1413393286805760512
1413393286855760384
1413393286905760512
1413393286955760384
1413393287005760512
1413393287055760384
1413393287105760512
1413393287155760384
1413393287205760512
1413393287255760384
1413393287305760512
1413393287355760384
1413393287405760512
1413393287455760384
1413393287505760512
1413393287555760384
1413393287605760512
1413393287655760384
1413393287705760512
1413393287755760384
1413393287805760512
1413393287855760384
1413393287905760512
1413393287955760384
1413393288005760512
1413393288055760384
1413393288105760512
1413393288155760384
1413393288205760512
1413393288255760384
1413393288305760512
1413393288355760384
1413393288405760512
1413393288455760384
1413393288505760512
1413393288555760384
1413393288605760512
1413393288655760384
1413393288705760512
1413393288755760384
1413393288805760512
1413393288855760384
1413393288905760512
1413393288955760384
1413393289005760512
1413393289055760384
1413393289105760512
1413393289155760384
1413393289205760512
1413393289255760384
1413393289305760512
1413393289355760384
1413393289405760512
1413393289455760384
1413393289505760512
1413393289555760384
1413393289605760512
1413393289655760384
1413393289705760512
1413393289755760384
1413393289805760512
1413393289855760384
1413393289905760512
1413393289955760384
1413393290005760512
1413393290055760384
1413393290105760512
1413393290155760384
1413393290205760512
1413393290255760384
1413393290305760512
1413393290355760384
1413393290405760512
1413393290455760384
1413393290505760512
1413393290555760384
1413393290605760512
1413393290655760384
1413393290705760512
1413393290755760384
1413393290805760512
1413393290855760384
1413393290905760512
1413393290955760384
1413393291005760512
1413393291055760384
1413393291105760512
1413393291155760384
1413393291205760512
1413393291255760384
1413393291305760512
1413393291355760384
1413393291405760512
1413393291455760384
1413393291505760512
1413393291555760384
1413393291605760512
1413393291655760384
1413393291705760512
1413393291755760384
1413393291805760512
1413393291855760384
1413393291905760512
1413393291955760384
1413393292005760512
1413393292055760384
1413393292105760512
1413393292155760384
1413393292205760512
1413393292255760384
1413393292305760512
1413393292355760384
1413393292405760512
1413393292455760384
1413393292505760512
1413393292555760384
1413393292605760512
1413393292655760384
1413393292705760512
1413393292755760384
1413393292805760512
1413393292855760384
1413393292905760512
1413393292955760384
1413393293005760512
1413393293055760384
1413393293105760512
1413393293155760384
1413393293205760512
1413393293255760384
1413393293305760512
1413393293355760384
1413393293405760512
1413393293455760384
1413393293505760512
1413393293555760384
1413393293605760512
1413393293655760384
1413393293705760512
1413393293755760384
1413393293805760512
1413393293855760384
1413393293905760512
1413393293955760384
1413393294005760512
1413393294055760384
1413393294105760512
1413393294155760384
1413393294205760512
1413393294255760384
1413393294305760512
1413393294355760384
1413393294405760512
1413393294455760384
1413393294505760512
1413393294555760384
1413393294605760512
1413393294655760384
1413393294705760512
1413393294755760384
1413393294805760512
1413393294855760384
1413393294905760512
1413393294955760384
1413393295005760512
1413393295055760384
1413393295105760512
1413393295155760384
1413393295205760512
1413393295255760384
1413393295305760512
1413393295355760384
1413393295405760512
1413393295455760384
1413393295505760512
1413393295555760384
1413393295605760512
1413393295655760384
1413393295705760512
1413393295755760384
1413393295805760512
1413393295855760384
1413393295905760512
1413393295955760384
1413393296005760512
1413393296055760384
1413393296105760512
1413393296155760384
1413393296205760512
1413393296255760384
1413393296305760512
1413393296355760384
1413393296405760512
1413393296455760384
1413393296505760512
1413393296555760384
1413393296605760512
1413393296655760384
1413393296705760512
1413393296755760384
1413393296805760512
1413393296855760384
1413393296905760512
1413393296955760384
1413393297005760512
1413393297055760384
1413393297105760512
1413393297155760384
1413393297205760512
1413393297255760384
1413393297305760512
1413393297355760384
1413393297405760512
1413393297455760384
1413393297505760512
1413393297555760384
1413393297605760512
1413393297655760384
1413393297705760512
1413393297755760384
1413393297805760512
1413393297855760384
1413393297905760512
1413393297955760384
1413393298005760512
1413393298055760384
1413393298105760512
1413393298155760384
1413393298205760512
1413393298255760384
1413393298305760512
1413393298355760384
1413393298405760512
1413393298455760384
1413393298505760512
1413393298555760384
1413393298605760512
1413393298655760384
1413393298705760512
1413393298755760384
1413393298805760512
1413393298855760384
1413393298905760512
1413393298955760384
1413393299005760512
1413393299055760384
1413393299105760512
1413393299155760384
1413393299205760512
1413393299255760384
1413393299305760512
1413393299355760384
1413393299405760512
1413393299455760384
1413393299505760512
1413393299555760384
1413393299605760512
1413393299655760384
1413393299705760512
1413393299755760384
1413393299805760512
1413393299855760384
1413393299905760512
1413393299955760384
1413393300005760512
1413393300055760384
1413393300105760512
1413393300155760384
1413393300205760512
1413393300255760384
1413393300305760512
1413393300355760384
1413393300405760512
1413393300455760384
1413393300505760512
1413393300555760384
1413393300605760512
1413393300655760384
1413393300705760512
1413393300755760384
1413393300805760512
1413393300855760384
1413393300905760512
1413393300955760384
1413393301005760512
1413393301055760384
1413393301105760512
1413393301155760384
1413393301205760512
1413393301255760384
1413393301305760512
1413393301355760384
1413393301405760512
1413393301455760384
1413393301505760512
1413393301555760384
1413393301605760512
1413393301655760384
1413393301705760512
1413393301755760384
1413393301805760512
1413393301855760384
1413393301905760512
1413393301955760384
1413393302005760512
1413393302055760384
1413393302105760512
1413393302155760384
1413393302205760512
1413393302255760384
1413393302305760512
1413393302355760384
1413393302405760512
1413393302455760384
1413393302505760512
1413393302555760384
1413393302605760512
1413393302655760384
1413393302705760512
1413393302755760384
1413393302805760512
1413393302855760384
1413393302905760512
1413393302955760384
1413393303005760512
1413393303055760384
1413393303105760512
1413393303155760384
1413393303205760512
1413393303255760384
1413393303305760512
1413393303355760384
1413393303405760512
1413393303455760384
1413393303505760512
1413393303555760384
1413393303605760512
1413393303655760384
1413393303705760512
1413393303755760384
1413393303805760512
1413393303855760384
1413393303905760512
1413393303955760384
1413393304005760512
1413393304055760384
1413393304105760512
1413393304155760384
1413393304205760512
1413393304255760384
1413393304305760512
1413393304355760384
1413393304405760512
1413393304455760384
1413393304505760512
1413393304555760384
1413393304605760512
1413393304655760384
1413393304705760512
1413393304755760384
1413393304805760512
1413393304855760384
1413393304905760512
1413393304955760384
1413393305005760512
1413393305055760384
1413393305105760512
1413393305155760384
1413393305205760512
1413393305255760384
1413393305305760512
1413393305355760384
1413393305405760512
1413393305455760384
1413393305505760512
1413393305555760384
1413393305605760512
1413393305655760384
1413393305705760512
1413393305755760384
1413393305805760512
1413393305855760384
1413393305905760512
1413393305955760384
1413393306005760512
1413393306055760384
1413393306105760512
1413393306155760384
1413393306205760512
1413393306255760384
1413393306305760512
1413393306355760384
1413393306405760512
1413393306455760384
1413393306505760512
1413393306555760384
1413393306605760512
1413393306655760384
1413393306705760512
1413393306755760384
1413393306805760512
1413393306855760384
1413393306905760512
1413393306955760384
1413393307005760512
1413393307055760384
1413393307105760512
1413393307155760384
1413393307205760512
1413393307255760384
1413393307305760512
1413393307355760384
1413393307405760512
1413393307455760384
1413393307505760512
1413393307555760384
1413393307605760512
1413393307655760384
1413393307705760512
1413393307755760384
1413393307805760512
1413393307855760384
1413393307905760512
1413393307955760384
1413393308005760512
1413393308055760384
1413393308105760512
1413393308155760384
1413393308205760512
1413393308255760384
1413393308305760512
1413393308355760384
1413393308405760512
1413393308455760384
1413393308505760512
1413393308555760384
1413393308605760512
1413393308655760384
1413393308705760512
1413393308755760384
1413393308805760512
1413393308855760384
1413393308905760512
1413393308955760384
1413393309005760512
1413393309055760384
1413393309105760512
1413393309155760384
1413393309205760512
1413393309255760384
1413393309305760512
1413393309355760384
1413393309405760512
1413393309455760384
1413393309505760512
1413393309555760384
1413393309605760512
1413393309655760384
1413393309705760512
1413393309755760384
1413393309805760512
1413393309855760384
1413393309905760512
1413393309955760384
1413393310005760512
1413393310055760384
1413393310105760512
1413393310155760384
1413393310205760512
1413393310255760384
1413393310305760512
1413393310355760384
1413393310405760512
1413393310455760384
1413393310505760512
1413393310555760384
1413393310605760512
1413393310655760384
1413393310705760512
1413393310755760384
1413393310805760512
1413393310855760384
1413393310905760512
1413393310955760384
1413393311005760512
1413393311055760384
1413393311105760512
1413393311155760384
1413393311205760512
1413393311255760384
1413393311305760512
1413393311355760384
1413393311405760512
1413393311455760384
1413393311505760512
1413393311555760384
1413393311605760512
1413393311655760384
1413393311705760512
1413393311755760384
1413393311805760512
1413393311855760384
1413393311905760512
1413393311955760384
1413393312005760512
1413393312055760384
1413393312105760512
1413393312155760384
1413393312205760512
1413393312255760384
1413393312305760512
1413393312355760384
1413393312405760512
1413393312455760384
1413393312505760512
1413393312555760384
1413393312605760512
1413393312655760384
1413393312705760512
1413393312755760384
1413393312805760512
1413393312855760384
1413393312905760512
1413393312955760384
1413393313005760512
1413393313055760384
1413393313105760512
1413393313155760384
1413393313205760512
1413393313255760384
1413393313305760512
1413393313355760384
1413393313405760512
1413393313455760384
1413393313505760512
1413393313555760384
1413393313605760512
1413393313655760384
1413393313705760512
1413393313755760384
1413393313805760512
1413393313855760384
1413393313905760512
1413393313955760384
1413393314005760512
1413393314055760384
1413393314105760512
1413393314155760384
1413393314205760512
1413393314255760384
1413393314305760512
1413393314355760384
1413393314405760512
1413393314455760384
1413393314505760512
1413393314555760384
1413393314605760512
1413393314655760384
1413393314705760512
1413393314755760384
1413393314805760512
1413393314855760384
1413393314905760512
1413393314955760384
1413393315005760512
1413393315055760384
1413393315105760512
1413393315155760384
1413393315205760512
1413393315255760384
1413393315305760512
1413393315355760384
1413393315405760512
1413393315455760384
1413393315505760512
1413393315555760384
1413393315605760512
1413393315655760384
1413393315705760512
1413393315755760384
1413393315805760512
1413393315855760384
1413393315905760512
1413393315955760384
1413393316005760512
1413393316055760384
1413393316105760512
1413393316155760384
1413393316205760512
1413393316255760384
1413393316305760512
1413393316355760384
1413393316405760512
1413393316455760384
1413393316505760512
1413393316555760384
1413393316605760512
1413393316655760384
1413393316705760512
1413393316755760384
1413393316805760512
1413393316855760384
1413393316905760512
1413393316955760384
1413393317005760512
1413393317055760384
1413393317105760512
1413393317155760384
1413393317205760512
1413393317255760384
1413393317305760512
1413393317355760384
1413393317405760512
1413393317455760384
1413393317505760512
1413393317555760384
1413393317605760512
1413393317655760384
1413393317705760512
1413393317755760384
1413393317805760512
1413393317855760384
1413393317905760512
1413393317955760384
1413393318005760512
1413393318055760384
1413393318105760512
1413393318155760384
1413393318205760512
1413393318255760384
1413393318305760512
1413393318355760384
1413393318405760512
1413393318455760384
1413393318505760512
1413393318555760384
1413393318605760512
1413393318655760384
1413393318705760512
1413393318755760384
1413393318805760512
1413393318855760384
1413393318905760512
1413393318955760384
1413393319005760512
1413393319055760384
1413393319105760512
1413393319155760384
1413393319205760512
1413393319255760384
1413393319305760512
1413393319355760384
1413393319405760512
1413393319455760384
1413393319505760512
1413393319555760384
1413393319605760512
1413393319655760384
1413393319705760512
1413393319755760384
1413393319805760512
1413393319855760384
1413393319905760512
1413393319955760384
1413393320005760512
1413393320055760384
1413393320105760512
1413393320155760384
1413393320205760512
1413393320255760384
1413393320305760512
1413393320355760384
1413393320405760512
1413393320455760384
1413393320505760512
1413393320555760384
1413393320605760512
1413393320655760384
1413393320705760512
1413393320755760384
1413393320805760512
1413393320855760384
1413393320905760512
1413393320955760384
1413393321005760512
1413393321055760384
1413393321105760512
1413393321155760384
1413393321205760512
1413393321255760384
1413393321305760512
1413393321355760384
1413393321405760512
1413393321455760384
1413393321505760512
1413393321555760384
1413393321605760512
1413393321655760384
1413393321705760512
1413393321755760384
1413393321805760512
1413393321855760384
1413393321905760512
1413393321955760384
1413393322005760512
1413393322055760384
1413393322105760512
1413393322155760384
1413393322205760512
1413393322255760384
1413393322305760512
1413393322355760384
1413393322405760512
1413393322455760384
1413393322505760512
1413393322555760384
1413393322605760512
1413393322655760384
1413393322705760512
1413393322755760384
1413393322805760512
1413393322855760384
1413393322905760512
1413393322955760384
1413393323005760512
1413393323055760384
1413393323105760512
1413393323155760384
1413393323205760512
1413393323255760384
1413393323305760512
1413393323355760384
1413393323405760512
1413393323455760384
1413393323505760512
1413393323555760384
1413393323605760512
1413393323655760384
1413393323705760512
1413393323755760384
1413393323805760512
1413393323855760384
1413393323905760512
1413393323955760384
1413393324005760512
1413393324055760384
1413393324105760512
1413393324155760384
1413393324205760512
1413393324255760384
1413393324305760512
1413393324355760384
1413393324405760512
1413393324455760384
1413393324505760512
1413393324555760384
1413393324605760512
1413393324655760384
1413393324705760512
1413393324755760384
1413393324805760512
1413393324855760384
1413393324905760512
1413393324955760384
1413393325005760512
1413393325055760384
1413393325105760512
1413393325155760384
1413393325205760512
1413393325255760384
1413393325305760512
1413393325355760384
1413393325405760512
1413393325455760384
1413393325505760512
1413393325555760384
1413393325605760512
1413393325655760384
1413393325705760512
1413393325755760384
1413393325805760512
1413393325855760384
1413393325905760512
1413393325955760384
1413393326005760512
1413393326055760384
1413393326105760512
1413393326155760384
1413393326205760512
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/V202.txt
================================================
1413393886005760512
1413393886055760384
1413393886105760512
1413393886155760384
1413393886205760512
1413393886255760384
1413393886305760512
1413393886355760384
1413393886405760512
1413393886455760384
1413393886505760512
1413393886555760384
1413393886605760512
1413393886655760384
1413393886705760512
1413393886755760384
1413393886805760512
1413393886855760384
1413393886905760512
1413393886955760384
1413393887005760512
1413393887055760384
1413393887105760512
1413393887155760384
1413393887205760512
1413393887255760384
1413393887305760512
1413393887355760384
1413393887405760512
1413393887455760384
1413393887505760512
1413393887555760384
1413393887605760512
1413393887655760384
1413393887705760512
1413393887755760384
1413393887805760512
1413393887855760384
1413393887905760512
1413393887955760384
1413393888005760512
1413393888055760384
1413393888105760512
1413393888155760384
1413393888205760512
1413393888255760384
1413393888305760512
1413393888355760384
1413393888405760512
1413393888455760384
1413393888505760512
1413393888555760384
1413393888605760512
1413393888655760384
1413393888705760512
1413393888755760384
1413393888805760512
1413393888855760384
1413393888905760512
1413393888955760384
1413393889005760512
1413393889055760384
1413393889105760512
1413393889155760384
1413393889205760512
1413393889255760384
1413393889305760512
1413393889355760384
1413393889405760512
1413393889455760384
1413393889505760512
1413393889555760384
1413393889605760512
1413393889655760384
1413393889705760512
1413393889755760384
1413393889805760512
1413393889855760384
1413393889905760512
1413393889955760384
1413393890005760512
1413393890055760384
1413393890105760512
1413393890155760384
1413393890205760512
1413393890255760384
1413393890305760512
1413393890355760384
1413393890405760512
1413393890455760384
1413393890505760512
1413393890555760384
1413393890605760512
1413393890655760384
1413393890705760512
1413393890755760384
1413393890805760512
1413393890855760384
1413393890905760512
1413393890955760384
1413393891005760512
1413393891055760384
1413393891105760512
1413393891155760384
1413393891205760512
1413393891255760384
1413393891305760512
1413393891355760384
1413393891405760512
1413393891455760384
1413393891505760512
1413393891555760384
1413393891605760512
1413393891655760384
1413393891705760512
1413393891755760384
1413393891805760512
1413393891855760384
1413393891905760512
1413393891955760384
1413393892005760512
1413393892055760384
1413393892105760512
1413393892155760384
1413393892205760512
1413393892255760384
1413393892305760512
1413393892355760384
1413393892405760512
1413393892455760384
1413393892505760512
1413393892555760384
1413393892605760512
1413393892655760384
1413393892705760512
1413393892755760384
1413393892805760512
1413393892855760384
1413393892905760512
1413393892955760384
1413393893005760512
1413393893055760384
1413393893105760512
1413393893155760384
1413393893205760512
1413393893255760384
1413393893305760512
1413393893355760384
1413393893405760512
1413393893455760384
1413393893505760512
1413393893555760384
1413393893605760512
1413393893655760384
1413393893705760512
1413393893755760384
1413393893805760512
1413393893855760384
1413393893905760512
1413393893955760384
1413393894005760512
1413393894055760384
1413393894105760512
1413393894155760384
1413393894205760512
1413393894255760384
1413393894305760512
1413393894355760384
1413393894405760512
1413393894455760384
1413393894505760512
1413393894555760384
1413393894605760512
1413393894655760384
1413393894705760512
1413393894755760384
1413393894805760512
1413393894855760384
1413393894905760512
1413393894955760384
1413393895005760512
1413393895055760384
1413393895105760512
1413393895155760384
1413393895205760512
1413393895255760384
1413393895305760512
1413393895355760384
1413393895405760512
1413393895455760384
1413393895505760512
1413393895555760384
1413393895605760512
1413393895655760384
1413393895705760512
1413393895755760384
1413393895805760512
1413393895855760384
1413393895905760512
1413393895955760384
1413393896005760512
1413393896055760384
1413393896105760512
1413393896155760384
1413393896205760512
1413393896255760384
1413393896305760512
1413393896355760384
1413393896405760512
1413393896455760384
1413393896505760512
1413393896555760384
1413393896605760512
1413393896655760384
1413393896705760512
1413393896755760384
1413393896805760512
1413393896855760384
1413393896905760512
1413393896955760384
1413393897005760512
1413393897055760384
1413393897105760512
1413393897155760384
1413393897205760512
1413393897255760384
1413393897305760512
1413393897355760384
1413393897405760512
1413393897455760384
1413393897505760512
1413393897555760384
1413393897605760512
1413393897655760384
1413393897705760512
1413393897755760384
1413393897805760512
1413393897855760384
1413393897905760512
1413393897955760384
1413393898005760512
1413393898055760384
1413393898105760512
1413393898155760384
1413393898205760512
1413393898255760384
1413393898305760512
1413393898355760384
1413393898405760512
1413393898455760384
1413393898505760512
1413393898555760384
1413393898605760512
1413393898655760384
1413393898705760512
1413393898755760384
1413393898805760512
1413393898855760384
1413393898905760512
1413393898955760384
1413393899005760512
1413393899055760384
1413393899105760512
1413393899155760384
1413393899205760512
1413393899255760384
1413393899305760512
1413393899355760384
1413393899405760512
1413393899455760384
1413393899505760512
1413393899555760384
1413393899605760512
1413393899655760384
1413393899705760512
1413393899755760384
1413393899805760512
1413393899855760384
1413393899905760512
1413393899955760384
1413393900005760512
1413393900055760384
1413393900105760512
1413393900155760384
1413393900205760512
1413393900255760384
1413393900305760512
1413393900355760384
1413393900405760512
1413393900455760384
1413393900505760512
1413393900555760384
1413393900605760512
1413393900655760384
1413393900705760512
1413393900755760384
1413393900805760512
1413393900855760384
1413393900905760512
1413393900955760384
1413393901005760512
1413393901055760384
1413393901105760512
1413393901155760384
1413393901205760512
1413393901255760384
1413393901305760512
1413393901355760384
1413393901405760512
1413393901455760384
1413393901505760512
1413393901555760384
1413393901605760512
1413393901655760384
1413393901705760512
1413393901755760384
1413393901805760512
1413393901855760384
1413393901905760512
1413393901955760384
1413393902005760512
1413393902055760384
1413393902105760512
1413393902155760384
1413393902205760512
1413393902255760384
1413393902305760512
1413393902355760384
1413393902405760512
1413393902455760384
1413393902505760512
1413393902555760384
1413393902605760512
1413393902655760384
1413393902705760512
1413393902755760384
1413393902805760512
1413393902855760384
1413393902905760512
1413393902955760384
1413393903005760512
1413393903055760384
1413393903105760512
1413393903155760384
1413393903205760512
1413393903255760384
1413393903305760512
1413393903355760384
1413393903405760512
1413393903455760384
1413393903505760512
1413393903555760384
1413393903605760512
1413393903655760384
1413393903705760512
1413393903755760384
1413393903805760512
1413393903855760384
1413393903905760512
1413393903955760384
1413393904005760512
1413393904055760384
1413393904105760512
1413393904155760384
1413393904205760512
1413393904255760384
1413393904305760512
1413393904355760384
1413393904405760512
1413393904455760384
1413393904505760512
1413393904555760384
1413393904605760512
1413393904655760384
1413393904705760512
1413393904755760384
1413393904805760512
1413393904855760384
1413393904905760512
1413393904955760384
1413393905005760512
1413393905055760384
1413393905105760512
1413393905155760384
1413393905205760512
1413393905255760384
1413393905305760512
1413393905355760384
1413393905405760512
1413393905455760384
1413393905505760512
1413393905555760384
1413393905605760512
1413393905655760384
1413393905705760512
1413393905755760384
1413393905805760512
1413393905855760384
1413393905905760512
1413393905955760384
1413393906005760512
1413393906055760384
1413393906105760512
1413393906155760384
1413393906205760512
1413393906255760384
1413393906305760512
1413393906355760384
1413393906405760512
1413393906455760384
1413393906505760512
1413393906555760384
1413393906605760512
1413393906655760384
1413393906705760512
1413393906755760384
1413393906805760512
1413393906855760384
1413393906905760512
1413393906955760384
1413393907005760512
1413393907055760384
1413393907105760512
1413393907155760384
1413393907205760512
1413393907255760384
1413393907305760512
1413393907355760384
1413393907405760512
1413393907455760384
1413393907505760512
1413393907555760384
1413393907605760512
1413393907655760384
1413393907705760512
1413393907755760384
1413393907805760512
1413393907855760384
1413393907905760512
1413393907955760384
1413393908005760512
1413393908055760384
1413393908105760512
1413393908155760384
1413393908205760512
1413393908255760384
1413393908305760512
1413393908355760384
1413393908405760512
1413393908455760384
1413393908505760512
1413393908555760384
1413393908605760512
1413393908655760384
1413393908705760512
1413393908755760384
1413393908805760512
1413393908855760384
1413393908905760512
1413393908955760384
1413393909005760512
1413393909055760384
1413393909105760512
1413393909155760384
1413393909205760512
1413393909255760384
1413393909305760512
1413393909355760384
1413393909405760512
1413393909455760384
1413393909505760512
1413393909555760384
1413393909605760512
1413393909655760384
1413393909705760512
1413393909755760384
1413393909805760512
1413393909855760384
1413393909905760512
1413393909955760384
1413393910005760512
1413393910055760384
1413393910105760512
1413393910155760384
1413393910205760512
1413393910255760384
1413393910305760512
1413393910355760384
1413393910405760512
1413393910455760384
1413393910505760512
1413393910555760384
1413393910605760512
1413393910655760384
1413393910705760512
1413393910755760384
1413393910805760512
1413393910855760384
1413393910905760512
1413393910955760384
1413393911005760512
1413393911055760384
1413393911105760512
1413393911155760384
1413393911205760512
1413393911255760384
1413393911305760512
1413393911355760384
1413393911405760512
1413393911455760384
1413393911505760512
1413393911555760384
1413393911605760512
1413393911655760384
1413393911705760512
1413393911755760384
1413393911805760512
1413393911855760384
1413393911905760512
1413393911955760384
1413393912005760512
1413393912055760384
1413393912105760512
1413393912155760384
1413393912205760512
1413393912255760384
1413393912305760512
1413393912355760384
1413393912405760512
1413393912455760384
1413393912505760512
1413393912555760384
1413393912605760512
1413393912655760384
1413393912705760512
1413393912755760384
1413393912805760512
1413393912855760384
1413393912905760512
1413393912955760384
1413393913005760512
1413393913055760384
1413393913105760512
1413393913155760384
1413393913205760512
1413393913255760384
1413393913305760512
1413393913355760384
1413393913405760512
1413393913455760384
1413393913505760512
1413393913555760384
1413393913605760512
1413393913655760384
1413393913705760512
1413393913755760384
1413393913805760512
1413393913855760384
1413393913905760512
1413393913955760384
1413393914005760512
1413393914055760384
1413393914105760512
1413393914155760384
1413393914205760512
1413393914255760384
1413393914305760512
1413393914355760384
1413393914405760512
1413393914455760384
1413393914505760512
1413393914555760384
1413393914605760512
1413393914655760384
1413393914705760512
1413393914755760384
1413393914805760512
1413393914855760384
1413393914905760512
1413393914955760384
1413393915005760512
1413393915055760384
1413393915105760512
1413393915155760384
1413393915205760512
1413393915255760384
1413393915305760512
1413393915355760384
1413393915405760512
1413393915455760384
1413393915505760512
1413393915555760384
1413393915605760512
1413393915655760384
1413393915705760512
1413393915755760384
1413393915805760512
1413393915855760384
1413393915905760512
1413393915955760384
1413393916005760512
1413393916055760384
1413393916105760512
1413393916155760384
1413393916205760512
1413393916255760384
1413393916305760512
1413393916355760384
1413393916405760512
1413393916455760384
1413393916505760512
1413393916555760384
1413393916605760512
1413393916655760384
1413393916705760512
1413393916755760384
1413393916805760512
1413393916855760384
1413393916905760512
1413393916955760384
1413393917005760512
1413393917055760384
1413393917105760512
1413393917155760384
1413393917205760512
1413393917255760384
1413393917305760512
1413393917355760384
1413393917405760512
1413393917455760384
1413393917505760512
1413393917555760384
1413393917605760512
1413393917655760384
1413393917705760512
1413393917755760384
1413393917805760512
1413393917855760384
1413393917905760512
1413393917955760384
1413393918005760512
1413393918055760384
1413393918105760512
1413393918155760384
1413393918205760512
1413393918255760384
1413393918305760512
1413393918355760384
1413393918405760512
1413393918455760384
1413393918505760512
1413393918555760384
1413393918605760512
1413393918655760384
1413393918705760512
1413393918755760384
1413393918805760512
1413393918855760384
1413393918905760512
1413393918955760384
1413393919005760512
1413393919055760384
1413393919105760512
1413393919155760384
1413393919205760512
1413393919255760384
1413393919305760512
1413393919355760384
1413393919405760512
1413393919455760384
1413393919505760512
1413393919555760384
1413393919605760512
1413393919655760384
1413393919705760512
1413393919755760384
1413393919805760512
1413393919855760384
1413393919905760512
1413393919955760384
1413393920005760512
1413393920055760384
1413393920105760512
1413393920155760384
1413393920205760512
1413393920255760384
1413393920305760512
1413393920355760384
1413393920405760512
1413393920455760384
1413393920505760512
1413393920555760384
1413393920605760512
1413393920655760384
1413393920705760512
1413393920755760384
1413393920805760512
1413393920855760384
1413393920905760512
1413393920955760384
1413393921005760512
1413393921055760384
1413393921105760512
1413393921155760384
1413393921205760512
1413393921255760384
1413393921305760512
1413393921355760384
1413393921405760512
1413393921455760384
1413393921505760512
1413393921555760384
1413393921605760512
1413393921655760384
1413393921705760512
1413393921755760384
1413393921805760512
1413393921855760384
1413393921905760512
1413393921955760384
1413393922005760512
1413393922055760384
1413393922105760512
1413393922155760384
1413393922205760512
1413393922255760384
1413393922305760512
1413393922355760384
1413393922405760512
1413393922455760384
1413393922505760512
1413393922555760384
1413393922605760512
1413393922655760384
1413393922705760512
1413393922755760384
1413393922805760512
1413393922855760384
1413393922905760512
1413393922955760384
1413393923005760512
1413393923055760384
1413393923105760512
1413393923155760384
1413393923205760512
1413393923255760384
1413393923305760512
1413393923355760384
1413393923405760512
1413393923455760384
1413393923505760512
1413393923555760384
1413393923605760512
1413393923655760384
1413393923705760512
1413393923755760384
1413393923805760512
1413393923855760384
1413393923905760512
1413393923955760384
1413393924005760512
1413393924055760384
1413393924105760512
1413393924155760384
1413393924205760512
1413393924255760384
1413393924305760512
1413393924355760384
1413393924405760512
1413393924455760384
1413393924505760512
1413393924555760384
1413393924605760512
1413393924655760384
1413393924705760512
1413393924755760384
1413393924805760512
1413393924855760384
1413393924905760512
1413393924955760384
1413393925005760512
1413393925055760384
1413393925105760512
1413393925155760384
1413393925205760512
1413393925255760384
1413393925305760512
1413393925355760384
1413393925405760512
1413393925455760384
1413393925505760512
1413393925555760384
1413393925605760512
1413393925655760384
1413393925705760512
1413393925755760384
1413393925805760512
1413393925855760384
1413393925905760512
1413393925955760384
1413393926005760512
1413393926055760384
1413393926105760512
1413393926155760384
1413393926205760512
1413393926255760384
1413393926305760512
1413393926355760384
1413393926405760512
1413393926455760384
1413393926505760512
1413393926555760384
1413393926605760512
1413393926655760384
1413393926705760512
1413393926755760384
1413393926805760512
1413393926855760384
1413393926905760512
1413393926955760384
1413393927005760512
1413393927055760384
1413393927105760512
1413393927155760384
1413393927205760512
1413393927255760384
1413393927305760512
1413393927355760384
1413393927405760512
1413393927455760384
1413393927505760512
1413393927555760384
1413393927605760512
1413393927655760384
1413393927705760512
1413393927755760384
1413393927805760512
1413393927855760384
1413393927905760512
1413393927955760384
1413393928005760512
1413393928055760384
1413393928105760512
1413393928155760384
1413393928205760512
1413393928255760384
1413393928305760512
1413393928355760384
1413393928405760512
1413393928455760384
1413393928505760512
1413393928555760384
1413393928605760512
1413393928655760384
1413393928705760512
1413393928755760384
1413393928805760512
1413393928855760384
1413393928905760512
1413393928955760384
1413393929005760512
1413393929055760384
1413393929105760512
1413393929155760384
1413393929205760512
1413393929255760384
1413393929305760512
1413393929355760384
1413393929405760512
1413393929455760384
1413393929505760512
1413393929555760384
1413393929605760512
1413393929655760384
1413393929705760512
1413393929755760384
1413393929805760512
1413393929855760384
1413393929905760512
1413393929955760384
1413393930005760512
1413393930055760384
1413393930105760512
1413393930155760384
1413393930205760512
1413393930255760384
1413393930305760512
1413393930355760384
1413393930405760512
1413393930455760384
1413393930505760512
1413393930555760384
1413393930605760512
1413393930655760384
1413393930705760512
1413393930755760384
1413393930805760512
1413393930855760384
1413393930905760512
1413393930955760384
1413393931005760512
1413393931055760384
1413393931105760512
1413393931155760384
1413393931205760512
1413393931255760384
1413393931305760512
1413393931355760384
1413393931405760512
1413393931455760384
1413393931505760512
1413393931555760384
1413393931605760512
1413393931655760384
1413393931705760512
1413393931755760384
1413393931805760512
1413393931855760384
1413393931905760512
1413393931955760384
1413393932005760512
1413393932055760384
1413393932105760512
1413393932155760384
1413393932205760512
1413393932255760384
1413393932305760512
1413393932355760384
1413393932405760512
1413393932455760384
1413393932505760512
1413393932555760384
1413393932605760512
1413393932655760384
1413393932705760512
1413393932755760384
1413393932805760512
1413393932855760384
1413393932905760512
1413393932955760384
1413393933005760512
1413393933055760384
1413393933105760512
1413393933155760384
1413393933205760512
1413393933255760384
1413393933305760512
1413393933355760384
1413393933405760512
1413393933455760384
1413393933505760512
1413393933555760384
1413393933605760512
1413393933655760384
1413393933705760512
1413393933755760384
1413393933805760512
1413393933855760384
1413393933905760512
1413393933955760384
1413393934005760512
1413393934055760384
1413393934105760512
1413393934155760384
1413393934205760512
1413393934255760384
1413393934305760512
1413393934355760384
1413393934405760512
1413393934455760384
1413393934505760512
1413393934555760384
1413393934605760512
1413393934655760384
1413393934705760512
1413393934755760384
1413393934805760512
1413393934855760384
1413393934905760512
1413393934955760384
1413393935005760512
1413393935055760384
1413393935105760512
1413393935155760384
1413393935205760512
1413393935255760384
1413393935305760512
1413393935355760384
1413393935405760512
1413393935455760384
1413393935505760512
1413393935555760384
1413393935605760512
1413393935655760384
1413393935705760512
1413393935755760384
1413393935805760512
1413393935855760384
1413393935905760512
1413393935955760384
1413393936005760512
1413393936055760384
1413393936105760512
1413393936155760384
1413393936205760512
1413393936255760384
1413393936305760512
1413393936355760384
1413393936405760512
1413393936455760384
1413393936505760512
1413393936555760384
1413393936605760512
1413393936655760384
1413393936705760512
1413393936755760384
1413393936805760512
1413393936855760384
1413393936905760512
1413393936955760384
1413393937005760512
1413393937055760384
1413393937105760512
1413393937155760384
1413393937205760512
1413393937255760384
1413393937305760512
1413393937355760384
1413393937405760512
1413393937455760384
1413393937505760512
1413393937555760384
1413393937605760512
1413393937655760384
1413393937705760512
1413393937755760384
1413393937805760512
1413393937855760384
1413393937905760512
1413393937955760384
1413393938005760512
1413393938055760384
1413393938105760512
1413393938155760384
1413393938205760512
1413393938255760384
1413393938305760512
1413393938355760384
1413393938405760512
1413393938455760384
1413393938505760512
1413393938555760384
1413393938605760512
1413393938655760384
1413393938705760512
1413393938755760384
1413393938805760512
1413393938855760384
1413393938905760512
1413393938955760384
1413393939005760512
1413393939055760384
1413393939105760512
1413393939155760384
1413393939205760512
1413393939255760384
1413393939305760512
1413393939355760384
1413393939405760512
1413393939455760384
1413393939505760512
1413393939555760384
1413393939605760512
1413393939655760384
1413393939705760512
1413393939755760384
1413393939805760512
1413393939855760384
1413393939905760512
1413393939955760384
1413393940005760512
1413393940055760384
1413393940105760512
1413393940155760384
1413393940205760512
1413393940255760384
1413393940305760512
1413393940355760384
1413393940405760512
1413393940455760384
1413393940505760512
1413393940555760384
1413393940605760512
1413393940655760384
1413393940705760512
1413393940755760384
1413393940805760512
1413393940855760384
1413393940905760512
1413393940955760384
1413393941005760512
1413393941055760384
1413393941105760512
1413393941155760384
1413393941205760512
1413393941255760384
1413393941305760512
1413393941355760384
1413393941405760512
1413393941455760384
1413393941505760512
1413393941555760384
1413393941605760512
1413393941655760384
1413393941705760512
1413393941755760384
1413393941805760512
1413393941855760384
1413393941905760512
1413393941955760384
1413393942005760512
1413393942055760384
1413393942105760512
1413393942155760384
1413393942205760512
1413393942255760384
1413393942305760512
1413393942355760384
1413393942405760512
1413393942455760384
1413393942505760512
1413393942555760384
1413393942605760512
1413393942655760384
1413393942705760512
1413393942755760384
1413393942805760512
1413393942855760384
1413393942905760512
1413393942955760384
1413393943005760512
1413393943055760384
1413393943105760512
1413393943155760384
1413393943205760512
1413393943255760384
1413393943305760512
1413393943355760384
1413393943405760512
1413393943455760384
1413393943505760512
1413393943555760384
1413393943605760512
1413393943655760384
1413393943705760512
1413393943755760384
1413393943805760512
1413393943855760384
1413393943905760512
1413393943955760384
1413393944005760512
1413393944055760384
1413393944105760512
1413393944155760384
1413393944205760512
1413393944255760384
1413393944305760512
1413393944355760384
1413393944405760512
1413393944455760384
1413393944505760512
1413393944555760384
1413393944605760512
1413393944655760384
1413393944705760512
1413393944755760384
1413393944805760512
1413393944855760384
1413393944905760512
1413393944955760384
1413393945005760512
1413393945055760384
1413393945105760512
1413393945155760384
1413393945205760512
1413393945255760384
1413393945305760512
1413393945355760384
1413393945405760512
1413393945455760384
1413393945505760512
1413393945555760384
1413393945605760512
1413393945655760384
1413393945705760512
1413393945755760384
1413393945805760512
1413393945855760384
1413393945905760512
1413393945955760384
1413393946005760512
1413393946055760384
1413393946105760512
1413393946155760384
1413393946205760512
1413393946255760384
1413393946305760512
1413393946355760384
1413393946405760512
1413393946455760384
1413393946505760512
1413393946555760384
1413393946605760512
1413393946655760384
1413393946705760512
1413393946755760384
1413393946805760512
1413393946855760384
1413393946905760512
1413393946955760384
1413393947005760512
1413393947055760384
1413393947105760512
1413393947155760384
1413393947205760512
1413393947255760384
1413393947305760512
1413393947355760384
1413393947405760512
1413393947455760384
1413393947505760512
1413393947555760384
1413393947605760512
1413393947655760384
1413393947705760512
1413393947755760384
1413393947805760512
1413393947855760384
1413393947905760512
1413393947955760384
1413393948005760512
1413393948055760384
1413393948105760512
1413393948155760384
1413393948205760512
1413393948255760384
1413393948305760512
1413393948355760384
1413393948405760512
1413393948455760384
1413393948505760512
1413393948555760384
1413393948605760512
1413393948655760384
1413393948705760512
1413393948755760384
1413393948805760512
1413393948855760384
1413393948905760512
1413393948955760384
1413393949005760512
1413393949055760384
1413393949105760512
1413393949155760384
1413393949205760512
1413393949255760384
1413393949305760512
1413393949355760384
1413393949405760512
1413393949455760384
1413393949505760512
1413393949555760384
1413393949605760512
1413393949655760384
1413393949705760512
1413393949755760384
1413393949805760512
1413393949855760384
1413393949905760512
1413393949955760384
1413393950005760512
1413393950055760384
1413393950105760512
1413393950155760384
1413393950205760512
1413393950255760384
1413393950305760512
1413393950355760384
1413393950405760512
1413393950455760384
1413393950505760512
1413393950555760384
1413393950605760512
1413393950655760384
1413393950705760512
1413393950755760384
1413393950805760512
1413393950855760384
1413393950905760512
1413393950955760384
1413393951005760512
1413393951055760384
1413393951105760512
1413393951155760384
1413393951205760512
1413393951255760384
1413393951305760512
1413393951355760384
1413393951405760512
1413393951455760384
1413393951505760512
1413393951555760384
1413393951605760512
1413393951655760384
1413393951705760512
1413393951755760384
1413393951805760512
1413393951855760384
1413393951905760512
1413393951955760384
1413393952005760512
1413393952055760384
1413393952105760512
1413393952155760384
1413393952205760512
1413393952255760384
1413393952305760512
1413393952355760384
1413393952405760512
1413393952455760384
1413393952505760512
1413393952555760384
1413393952605760512
1413393952655760384
1413393952705760512
1413393952755760384
1413393952805760512
1413393952855760384
1413393952905760512
1413393952955760384
1413393953005760512
1413393953055760384
1413393953105760512
1413393953155760384
1413393953205760512
1413393953255760384
1413393953305760512
1413393953355760384
1413393953405760512
1413393953455760384
1413393953505760512
1413393953555760384
1413393953605760512
1413393953655760384
1413393953705760512
1413393953755760384
1413393953805760512
1413393953855760384
1413393953905760512
1413393953955760384
1413393954005760512
1413393954055760384
1413393954105760512
1413393954155760384
1413393954205760512
1413393954255760384
1413393954305760512
1413393954355760384
1413393954405760512
1413393954455760384
1413393954505760512
1413393954555760384
1413393954605760512
1413393954655760384
1413393954705760512
1413393954755760384
1413393954805760512
1413393954855760384
1413393954905760512
1413393954955760384
1413393955005760512
1413393955055760384
1413393955105760512
1413393955155760384
1413393955205760512
1413393955255760384
1413393955305760512
1413393955355760384
1413393955405760512
1413393955455760384
1413393955505760512
1413393955555760384
1413393955605760512
1413393955655760384
1413393955705760512
1413393955755760384
1413393955805760512
1413393955855760384
1413393955905760512
1413393955955760384
1413393956005760512
1413393956055760384
1413393956105760512
1413393956155760384
1413393956205760512
1413393956255760384
1413393956305760512
1413393956355760384
1413393956405760512
1413393956455760384
1413393956505760512
1413393956555760384
1413393956605760512
1413393956655760384
1413393956705760512
1413393956755760384
1413393956805760512
1413393956855760384
1413393956905760512
1413393956955760384
1413393957005760512
1413393957055760384
1413393957105760512
1413393957155760384
1413393957205760512
1413393957255760384
1413393957305760512
1413393957355760384
1413393957405760512
1413393957455760384
1413393957505760512
1413393957555760384
1413393957605760512
1413393957655760384
1413393957705760512
1413393957755760384
1413393957805760512
1413393957855760384
1413393957905760512
1413393957955760384
1413393958005760512
1413393958055760384
1413393958105760512
1413393958155760384
1413393958205760512
1413393958255760384
1413393958305760512
1413393958355760384
1413393958405760512
1413393958455760384
1413393958505760512
1413393958555760384
1413393958605760512
1413393958655760384
1413393958705760512
1413393958755760384
1413393958805760512
1413393958855760384
1413393958905760512
1413393958955760384
1413393959005760512
1413393959055760384
1413393959105760512
1413393959155760384
1413393959205760512
1413393959255760384
1413393959305760512
1413393959355760384
1413393959405760512
1413393959455760384
1413393959505760512
1413393959555760384
1413393959605760512
1413393959655760384
1413393959705760512
1413393959755760384
1413393959805760512
1413393959855760384
1413393959905760512
1413393959955760384
1413393960005760512
1413393960055760384
1413393960105760512
1413393960155760384
1413393960205760512
1413393960255760384
1413393960305760512
1413393960355760384
1413393960405760512
1413393960455760384
1413393960505760512
1413393960555760384
1413393960605760512
1413393960655760384
1413393960705760512
1413393960755760384
1413393960805760512
1413393960855760384
1413393960905760512
1413393960955760384
1413393961005760512
1413393961055760384
1413393961105760512
1413393961155760384
1413393961205760512
1413393961255760384
1413393961305760512
1413393961355760384
1413393961405760512
1413393961455760384
1413393961505760512
1413393961555760384
1413393961605760512
1413393961655760384
1413393961705760512
1413393961755760384
1413393961805760512
1413393961855760384
1413393961905760512
1413393961955760384
1413393962005760512
1413393962055760384
1413393962105760512
1413393962155760384
1413393962205760512
1413393962255760384
1413393962305760512
1413393962355760384
1413393962405760512
1413393962455760384
1413393962505760512
1413393962555760384
1413393962605760512
1413393962655760384
1413393962705760512
1413393962755760384
1413393962805760512
1413393962855760384
1413393962905760512
1413393962955760384
1413393963005760512
1413393963055760384
1413393963105760512
1413393963155760384
1413393963205760512
1413393963255760384
1413393963305760512
1413393963355760384
1413393963405760512
1413393963455760384
1413393963505760512
1413393963555760384
1413393963605760512
1413393963655760384
1413393963705760512
1413393963755760384
1413393963805760512
1413393963855760384
1413393963905760512
1413393963955760384
1413393964005760512
1413393964055760384
1413393964105760512
1413393964155760384
1413393964205760512
1413393964255760384
1413393964305760512
1413393964355760384
1413393964405760512
1413393964455760384
1413393964505760512
1413393964555760384
1413393964605760512
1413393964655760384
1413393964705760512
1413393964755760384
1413393964805760512
1413393964855760384
1413393964905760512
1413393964955760384
1413393965005760512
1413393965055760384
1413393965105760512
1413393965155760384
1413393965205760512
1413393965255760384
1413393965305760512
1413393965355760384
1413393965405760512
1413393965455760384
1413393965505760512
1413393965555760384
1413393965605760512
1413393965655760384
1413393965705760512
1413393965755760384
1413393965805760512
1413393965855760384
1413393965905760512
1413393965955760384
1413393966005760512
1413393966055760384
1413393966105760512
1413393966155760384
1413393966205760512
1413393966255760384
1413393966305760512
1413393966355760384
1413393966405760512
1413393966455760384
1413393966505760512
1413393966555760384
1413393966605760512
1413393966655760384
1413393966705760512
1413393966755760384
1413393966805760512
1413393966855760384
1413393966905760512
1413393966955760384
1413393967005760512
1413393967055760384
1413393967105760512
1413393967155760384
1413393967205760512
1413393967255760384
1413393967305760512
1413393967355760384
1413393967405760512
1413393967455760384
1413393967505760512
1413393967555760384
1413393967605760512
1413393967655760384
1413393967705760512
1413393967755760384
1413393967805760512
1413393967855760384
1413393967905760512
1413393967955760384
1413393968005760512
1413393968055760384
1413393968105760512
1413393968155760384
1413393968205760512
1413393968255760384
1413393968305760512
1413393968355760384
1413393968405760512
1413393968455760384
1413393968505760512
1413393968555760384
1413393968605760512
1413393968655760384
1413393968705760512
1413393968755760384
1413393968805760512
1413393968855760384
1413393968905760512
1413393968955760384
1413393969005760512
1413393969055760384
1413393969105760512
1413393969155760384
1413393969205760512
1413393969255760384
1413393969305760512
1413393969355760384
1413393969405760512
1413393969455760384
1413393969505760512
1413393969555760384
1413393969605760512
1413393969655760384
1413393969705760512
1413393969755760384
1413393969805760512
1413393969855760384
1413393969905760512
1413393969955760384
1413393970005760512
1413393970055760384
1413393970105760512
1413393970155760384
1413393970205760512
1413393970255760384
1413393970305760512
1413393970355760384
1413393970405760512
1413393970455760384
1413393970505760512
1413393970555760384
1413393970605760512
1413393970655760384
1413393970705760512
1413393970755760384
1413393970805760512
1413393970855760384
1413393970905760512
1413393970955760384
1413393971005760512
1413393971055760384
1413393971105760512
1413393971155760384
1413393971205760512
1413393971255760384
1413393971305760512
1413393971355760384
1413393971405760512
1413393971455760384
1413393971505760512
1413393971555760384
1413393971605760512
1413393971655760384
1413393971705760512
1413393971755760384
1413393971805760512
1413393971855760384
1413393971905760512
1413393971955760384
1413393972005760512
1413393972055760384
1413393972105760512
1413393972155760384
1413393972205760512
1413393972255760384
1413393972305760512
1413393972355760384
1413393972405760512
1413393972455760384
1413393972505760512
1413393972555760384
1413393972605760512
1413393972655760384
1413393972705760512
1413393972755760384
1413393972805760512
1413393972855760384
1413393972905760512
1413393972955760384
1413393973005760512
1413393973055760384
1413393973105760512
1413393973155760384
1413393973205760512
1413393973255760384
1413393973305760512
1413393973355760384
1413393973405760512
1413393973455760384
1413393973505760512
1413393973555760384
1413393973605760512
1413393973655760384
1413393973705760512
1413393973755760384
1413393973805760512
1413393973855760384
1413393973905760512
1413393973955760384
1413393974005760512
1413393974055760384
1413393974105760512
1413393974155760384
1413393974205760512
1413393974255760384
1413393974305760512
1413393974355760384
1413393974405760512
1413393974455760384
1413393974505760512
1413393974555760384
1413393974605760512
1413393974655760384
1413393974705760512
1413393974755760384
1413393974805760512
1413393974855760384
1413393974905760512
1413393974955760384
1413393975005760512
1413393975055760384
1413393975105760512
1413393975155760384
1413393975205760512
1413393975255760384
1413393975305760512
1413393975355760384
1413393975405760512
1413393975455760384
1413393975505760512
1413393975555760384
1413393975605760512
1413393975655760384
1413393975705760512
1413393975755760384
1413393975805760512
1413393975855760384
1413393975905760512
1413393975955760384
1413393976005760512
1413393976055760384
1413393976105760512
1413393976155760384
1413393976205760512
1413393976255760384
1413393976305760512
1413393976355760384
1413393976405760512
1413393976455760384
1413393976505760512
1413393976555760384
1413393976605760512
1413393976655760384
1413393976705760512
1413393976755760384
1413393976805760512
1413393976855760384
1413393976905760512
1413393976955760384
1413393977005760512
1413393977055760384
1413393977105760512
1413393977155760384
1413393977205760512
1413393977255760384
1413393977305760512
1413393977355760384
1413393977405760512
1413393977455760384
1413393977505760512
1413393977555760384
1413393977605760512
1413393977655760384
1413393977705760512
1413393977755760384
1413393977805760512
1413393977855760384
1413393977905760512
1413393977955760384
1413393978005760512
1413393978055760384
1413393978105760512
1413393978155760384
1413393978205760512
1413393978255760384
1413393978305760512
1413393978355760384
1413393978405760512
1413393978455760384
1413393978505760512
1413393978555760384
1413393978605760512
1413393978655760384
1413393978705760512
1413393978755760384
1413393978805760512
1413393978855760384
1413393978905760512
1413393978955760384
1413393979005760512
1413393979055760384
1413393979105760512
1413393979155760384
1413393979205760512
1413393979255760384
1413393979305760512
1413393979355760384
1413393979405760512
1413393979455760384
1413393979505760512
1413393979555760384
1413393979605760512
1413393979655760384
1413393979705760512
1413393979755760384
1413393979805760512
1413393979855760384
1413393979905760512
1413393979955760384
1413393980005760512
1413393980055760384
1413393980105760512
1413393980155760384
1413393980205760512
1413393980255760384
1413393980305760512
1413393980355760384
1413393980405760512
1413393980455760384
1413393980505760512
1413393980555760384
1413393980605760512
1413393980655760384
1413393980705760512
1413393980755760384
1413393980805760512
1413393980855760384
1413393980905760512
1413393980955760384
1413393981005760512
1413393981055760384
1413393981105760512
1413393981155760384
1413393981205760512
1413393981255760384
1413393981305760512
1413393981355760384
1413393981405760512
1413393981455760384
1413393981505760512
1413393981555760384
1413393981605760512
1413393981655760384
1413393981705760512
1413393981755760384
1413393981805760512
1413393981855760384
1413393981905760512
1413393981955760384
1413393982005760512
1413393982055760384
1413393982105760512
1413393982155760384
1413393982205760512
1413393982255760384
1413393982305760512
1413393982355760384
1413393982405760512
1413393982455760384
1413393982505760512
1413393982555760384
1413393982605760512
1413393982655760384
1413393982705760512
1413393982755760384
1413393982805760512
1413393982855760384
1413393982905760512
1413393982955760384
1413393983005760512
1413393983055760384
1413393983105760512
1413393983155760384
1413393983205760512
1413393983255760384
1413393983305760512
1413393983355760384
1413393983405760512
1413393983455760384
1413393983505760512
1413393983555760384
1413393983605760512
1413393983655760384
1413393983705760512
1413393983755760384
1413393983805760512
1413393983855760384
1413393983905760512
1413393983955760384
1413393984005760512
1413393984055760384
1413393984105760512
1413393984155760384
1413393984205760512
1413393984255760384
1413393984305760512
1413393984355760384
1413393984405760512
1413393984455760384
1413393984505760512
1413393984555760384
1413393984605760512
1413393984655760384
1413393984705760512
1413393984755760384
1413393984805760512
1413393984855760384
1413393984905760512
1413393984955760384
1413393985005760512
1413393985055760384
1413393985105760512
1413393985155760384
1413393985205760512
1413393985255760384
1413393985305760512
1413393985355760384
1413393985405760512
1413393985455760384
1413393985505760512
1413393985555760384
1413393985605760512
1413393985655760384
1413393985705760512
1413393985755760384
1413393985805760512
1413393985855760384
1413393985905760512
1413393985955760384
1413393986005760512
1413393986055760384
1413393986105760512
1413393986155760384
1413393986205760512
1413393986255760384
1413393986305760512
1413393986355760384
1413393986405760512
1413393986455760384
1413393986505760512
1413393986555760384
1413393986605760512
1413393986655760384
1413393986705760512
1413393986755760384
1413393986805760512
1413393986855760384
1413393986905760512
1413393986955760384
1413393987005760512
1413393987055760384
1413393987105760512
1413393987155760384
1413393987205760512
1413393987255760384
1413393987305760512
1413393987355760384
1413393987405760512
1413393987455760384
1413393987505760512
1413393987555760384
1413393987605760512
1413393987655760384
1413393987705760512
1413393987755760384
1413393987805760512
1413393987855760384
1413393987905760512
1413393987955760384
1413393988005760512
1413393988055760384
1413393988105760512
1413393988155760384
1413393988205760512
1413393988255760384
1413393988305760512
1413393988355760384
1413393988405760512
1413393988455760384
1413393988505760512
1413393988555760384
1413393988605760512
1413393988655760384
1413393988705760512
1413393988755760384
1413393988805760512
1413393988855760384
1413393988905760512
1413393988955760384
1413393989005760512
1413393989055760384
1413393989105760512
1413393989155760384
1413393989205760512
1413393989255760384
1413393989305760512
1413393989355760384
1413393989405760512
1413393989455760384
1413393989505760512
1413393989555760384
1413393989605760512
1413393989655760384
1413393989705760512
1413393989755760384
1413393989805760512
1413393989855760384
1413393989905760512
1413393989955760384
1413393990005760512
1413393990055760384
1413393990105760512
1413393990155760384
1413393990205760512
1413393990255760384
1413393990305760512
1413393990355760384
1413393990405760512
1413393990455760384
1413393990505760512
1413393990555760384
1413393990605760512
1413393990655760384
1413393990705760512
1413393990755760384
1413393990805760512
1413393990855760384
1413393990905760512
1413393990955760384
1413393991005760512
1413393991055760384
1413393991105760512
1413393991155760384
1413393991205760512
1413393991255760384
1413393991305760512
1413393991355760384
1413393991405760512
1413393991455760384
1413393991505760512
1413393991555760384
1413393991605760512
1413393991655760384
1413393991705760512
1413393991755760384
1413393991805760512
1413393991855760384
1413393991905760512
1413393991955760384
1413393992005760512
1413393992055760384
1413393992105760512
1413393992155760384
1413393992205760512
1413393992255760384
1413393992305760512
1413393992355760384
1413393992405760512
1413393992455760384
1413393992505760512
1413393992555760384
1413393992605760512
1413393992655760384
1413393992705760512
1413393992755760384
1413393992805760512
1413393992855760384
1413393992905760512
1413393992955760384
1413393993005760512
1413393993055760384
1413393993105760512
1413393993155760384
1413393993205760512
1413393993255760384
1413393993305760512
1413393993355760384
1413393993405760512
1413393993455760384
1413393993505760512
1413393993555760384
1413393993605760512
1413393993655760384
1413393993705760512
1413393993755760384
1413393993805760512
1413393993855760384
1413393993905760512
1413393993955760384
1413393994005760512
1413393994055760384
1413393994105760512
1413393994155760384
1413393994205760512
1413393994255760384
1413393994305760512
1413393994355760384
1413393994405760512
1413393994455760384
1413393994505760512
1413393994555760384
1413393994605760512
1413393994655760384
1413393994705760512
1413393994755760384
1413393994805760512
1413393994855760384
1413393994905760512
1413393994955760384
1413393995005760512
1413393995055760384
1413393995105760512
1413393995155760384
1413393995205760512
1413393995255760384
1413393995305760512
1413393995355760384
1413393995405760512
1413393995455760384
1413393995505760512
1413393995555760384
1413393995605760512
1413393995655760384
1413393995705760512
1413393995755760384
1413393995805760512
1413393995855760384
1413393995905760512
1413393995955760384
1413393996005760512
1413393996055760384
1413393996105760512
1413393996155760384
1413393996205760512
1413393996255760384
1413393996305760512
1413393996355760384
1413393996405760512
1413393996455760384
1413393996505760512
1413393996555760384
1413393996605760512
1413393996655760384
1413393996705760512
1413393996755760384
1413393996805760512
1413393996855760384
1413393996905760512
1413393996955760384
1413393997005760512
1413393997055760384
1413393997105760512
1413393997155760384
1413393997205760512
1413393997255760384
1413393997305760512
1413393997355760384
1413393997405760512
1413393997455760384
1413393997505760512
1413393997555760384
1413393997605760512
1413393997655760384
1413393997705760512
1413393997755760384
1413393997805760512
1413393997855760384
1413393997905760512
1413393997955760384
1413393998005760512
1413393998055760384
1413393998105760512
1413393998155760384
1413393998205760512
1413393998255760384
1413393998305760512
1413393998355760384
1413393998405760512
1413393998455760384
1413393998505760512
1413393998555760384
1413393998605760512
1413393998655760384
1413393998705760512
1413393998755760384
1413393998805760512
1413393998855760384
1413393998905760512
1413393998955760384
1413393999005760512
1413393999055760384
1413393999105760512
1413393999155760384
1413393999205760512
1413393999255760384
1413393999305760512
1413393999355760384
1413393999405760512
1413393999455760384
1413393999505760512
1413393999555760384
1413393999605760512
1413393999655760384
1413393999705760512
1413393999755760384
1413393999805760512
1413393999855760384
1413393999905760512
1413393999955760384
1413394000005760512
1413394000055760384
1413394000105760512
1413394000155760384
1413394000205760512
1413394000255760384
1413394000305760512
1413394000355760384
1413394000405760512
1413394000455760384
1413394000505760512
1413394000555760384
1413394000605760512
1413394000655760384
1413394000705760512
1413394000755760384
1413394000805760512
1413394000855760384
1413394000905760512
1413394000955760384
1413394001005760512
1413394001055760384
1413394001105760512
1413394001155760384
1413394001205760512
1413394001255760384
1413394001305760512
1413394001355760384
1413394001405760512
1413394001455760384
1413394001505760512
1413394001555760384
1413394001605760512
1413394001655760384
1413394001705760512
1413394001755760384
1413394001805760512
1413394001855760384
1413394001905760512
1413394001955760384
1413394002005760512
1413394002055760384
1413394002105760512
1413394002155760384
1413394002205760512
1413394002255760384
1413394002305760512
1413394002355760384
1413394002405760512
1413394002455760384
1413394002505760512
1413394002555760384
1413394002605760512
1413394002655760384
1413394002705760512
1413394002755760384
1413394002805760512
1413394002855760384
1413394002905760512
1413394002955760384
1413394003005760512
1413394003055760384
1413394003105760512
1413394003155760384
1413394003205760512
1413394003255760384
1413394003305760512
1413394003355760384
================================================
FILE: Examples/Monocular/EuRoC_TimeStamps/V203.txt
================================================
1413394881555760384
1413394881605760512
1413394881655760384
1413394881705760512
1413394881755760384
1413394881805760512
1413394881855760384
1413394881905760512
1413394881955760384
1413394882005760512
1413394882055760384
1413394882105760512
1413394882155760384
1413394882205760512
1413394882255760384
1413394882305760512
1413394882355760384
1413394882405760512
1413394882455760384
1413394882505760512
1413394882555760384
1413394882605760512
1413394882655760384
1413394882705760512
1413394882755760384
1413394882805760512
1413394882855760384
1413394882905760512
1413394882955760384
1413394883005760512
1413394883055760384
1413394883105760512
1413394883155760384
1413394883205760512
1413394883255760384
1413394883305760512
1413394883355760384
1413394883405760512
1413394883455760384
1413394883505760512
1413394883555760384
1413394883605760512
1413394883655760384
1413394883705760512
1413394883755760384
1413394883805760512
1413394883855760384
1413394883905760512
1413394883955760384
1413394884005760512
1413394884055760384
1413394884105760512
1413394884155760384
1413394884205760512
1413394884255760384
1413394884305760512
1413394884355760384
1413394884405760512
1413394884455760384
1413394884505760512
1413394884555760384
1413394884605760512
1413394884655760384
1413394884705760512
1413394884755760384
1413394884805760512
1413394884855760384
1413394884905760512
1413394884955760384
1413394885005760512
1413394885055760384
1413394885105760512
1413394885155760384
1413394885205760512
1413394885255760384
1413394885305760512
1413394885355760384
1413394885405760512
1413394885455760384
1413394885505760512
1413394885555760384
1413394885605760512
1413394885655760384
1413394885705760512
1413394885755760384
1413394885805760512
1413394885855760384
1413394885905760512
1413394885955760384
1413394886005760512
1413394886055760384
1413394886105760512
1413394886155760384
1413394886205760512
1413394886255760384
1413394886305760512
1413394886355760384
1413394886405760512
1413394886455760384
1413394886505760512
1413394886555760384
1413394886605760512
1413394886655760384
1413394886705760512
1413394886755760384
1413394886805760512
1413394886855760384
1413394886905760512
1413394886955760384
1413394887005760512
1413394887055760384
1413394887105760512
1413394887155760384
1413394887205760512
1413394887255760384
1413394887305760512
1413394887355760384
1413394887405760512
1413394887455760384
1413394887505760512
1413394887555760384
1413394887605760512
1413394887655760384
1413394887705760512
1413394887755760384
1413394887805760512
1413394887855760384
1413394887905760512
1413394887955760384
1413394888005760512
1413394888055760384
1413394888105760512
1413394888155760384
1413394888205760512
1413394888255760384
1413394888305760512
1413394888355760384
1413394888405760512
1413394888455760384
1413394888505760512
1413394888555760384
1413394888605760512
1413394888655760384
1413394888705760512
1413394888755760384
1413394888805760512
1413394888855760384
1413394888905760512
1413394888955760384
1413394889005760512
1413394889055760384
1413394889105760512
1413394889155760384
1413394889205760512
1413394889255760384
1413394889305760512
1413394889355760384
1413394889405760512
1413394889455760384
1413394889505760512
1413394889555760384
1413394889605760512
1413394889655760384
1413394889705760512
1413394889755760384
1413394889805760512
1413394889855760384
1413394889905760512
1413394889955760384
1413394890005760512
1413394890055760384
1413394890105760512
1413394890155760384
1413394890205760512
1413394890255760384
1413394890305760512
1413394890355760384
1413394890405760512
1413394890455760384
1413394890505760512
1413394890555760384
1413394890605760512
1413394890655760384
1413394890705760512
1413394890755760384
1413394890805760512
1413394890855760384
1413394890905760512
1413394890955760384
1413394891005760512
1413394891055760384
1413394891105760512
1413394891155760384
1413394891205760512
1413394891255760384
1413394891305760512
1413394891355760384
1413394891405760512
1413394891455760384
1413394891505760512
1413394891555760384
1413394891605760512
1413394891655760384
1413394891705760512
1413394891755760384
1413394891805760512
1413394891855760384
1413394891905760512
1413394891955760384
1413394892005760512
1413394892055760384
1413394892105760512
1413394892155760384
1413394892205760512
1413394892255760384
1413394892305760512
1413394892355760384
1413394892405760512
1413394892455760384
1413394892505760512
1413394892555760384
1413394892605760512
1413394892655760384
1413394892705760512
1413394892755760384
1413394892805760512
1413394892855760384
1413394892905760512
1413394892955760384
1413394893005760512
1413394893055760384
1413394893105760512
1413394893155760384
1413394893205760512
1413394893255760384
1413394893305760512
1413394893355760384
1413394893405760512
1413394893455760384
1413394893505760512
1413394893555760384
1413394893605760512
1413394893655760384
1413394893705760512
1413394893755760384
1413394893805760512
1413394893855760384
1413394893905760512
1413394893955760384
1413394894005760512
1413394894055760384
1413394894105760512
1413394894155760384
1413394894205760512
1413394894255760384
1413394894305760512
1413394894355760384
1413394894405760512
1413394894455760384
1413394894505760512
1413394894555760384
1413394894605760512
1413394894655760384
1413394894705760512
1413394894755760384
1413394894805760512
1413394894855760384
1413394894905760512
1413394894955760384
1413394895005760512
1413394895055760384
1413394895105760512
1413394895155760384
1413394895205760512
1413394895255760384
1413394895305760512
1413394895355760384
1413394895405760512
1413394895455760384
1413394895505760512
1413394895555760384
1413394895605760512
1413394895655760384
1413394895705760512
1413394895755760384
1413394895805760512
1413394895855760384
1413394895905760512
1413394895955760384
1413394896005760512
1413394896055760384
1413394896105760512
1413394896155760384
1413394896205760512
1413394896255760384
1413394896305760512
1413394896355760384
1413394896405760512
1413394896455760384
1413394896505760512
1413394896555760384
1413394896605760512
1413394896655760384
1413394896705760512
1413394896755760384
1413394896805760512
1413394896855760384
1413394896905760512
1413394896955760384
1413394897005760512
1413394897055760384
1413394897105760512
1413394897155760384
1413394897205760512
1413394897255760384
1413394897305760512
1413394897355760384
1413394897405760512
1413394897455760384
1413394897505760512
1413394897555760384
1413394897605760512
1413394897655760384
1413394897705760512
1413394897755760384
1413394897805760512
1413394897855760384
1413394897905760512
1413394897955760384
1413394898005760512
1413394898055760384
1413394898105760512
1413394898155760384
1413394898205760512
1413394898255760384
1413394898305760512
1413394898355760384
1413394898405760512
1413394898455760384
1413394898505760512
1413394898555760384
1413394898605760512
1413394898655760384
1413394898705760512
1413394898755760384
1413394898805760512
1413394898855760384
1413394898905760512
1413394898955760384
1413394899005760512
1413394899055760384
1413394899105760512
1413394899155760384
1413394899205760512
1413394899255760384
1413394899305760512
1413394899355760384
1413394899405760512
1413394899455760384
1413394899505760512
1413394899555760384
1413394899605760512
1413394899655760384
1413394899705760512
1413394899755760384
1413394899805760512
1413394899855760384
1413394899905760512
1413394899955760384
1413394900005760512
1413394900055760384
1413394900105760512
1413394900155760384
1413394900205760512
1413394900255760384
1413394900305760512
1413394900355760384
1413394900405760512
1413394900455760384
1413394900505760512
1413394900555760384
1413394900605760512
1413394900655760384
1413394900705760512
1413394900755760384
1413394900805760512
1413394900855760384
1413394900905760512
1413394900955760384
1413394901005760512
1413394901055760384
1413394901105760512
1413394901155760384
1413394901205760512
1413394901255760384
1413394901305760512
1413394901355760384
1413394901405760512
1413394901455760384
1413394901505760512
1413394901555760384
1413394901605760512
1413394901655760384
1413394901705760512
1413394901755760384
1413394901805760512
1413394901855760384
1413394901905760512
1413394901955760384
1413394902005760512
1413394902055760384
1413394902105760512
1413394902155760384
1413394902205760512
1413394902255760384
1413394902305760512
1413394902355760384
1413394902405760512
1413394902455760384
1413394902505760512
1413394902555760384
1413394902605760512
1413394902655760384
1413394902705760512
1413394902755760384
1413394902805760512
1413394902855760384
1413394902905760512
1413394902955760384
1413394903055760384
1413394903155760384
1413394903255760384
1413394903355760384
1413394903455760384
1413394903555760384
1413394903605760512
1413394903655760384
1413394903705760512
1413394903755760384
1413394903805760512
1413394903855760384
1413394903905760512
1413394903955760384
1413394904005760512
1413394904055760384
1413394904105760512
1413394904155760384
1413394904205760512
1413394904255760384
1413394904305760512
1413394904355760384
1413394904405760512
1413394904455760384
1413394904505760512
1413394904555760384
1413394904605760512
1413394904655760384
1413394904705760512
1413394904755760384
1413394904805760512
1413394904855760384
1413394904905760512
1413394904955760384
1413394905005760512
1413394905055760384
1413394905105760512
1413394905155760384
1413394905205760512
1413394905255760384
1413394905305760512
1413394905355760384
1413394905405760512
1413394905455760384
1413394905505760512
1413394905555760384
1413394905605760512
1413394905655760384
1413394905705760512
1413394905755760384
1413394905805760512
1413394905855760384
1413394905905760512
1413394905955760384
1413394906005760512
1413394906055760384
1413394906105760512
1413394906155760384
1413394906205760512
1413394906255760384
1413394906305760512
1413394906355760384
1413394906405760512
1413394906455760384
1413394906505760512
1413394906555760384
1413394906605760512
1413394906655760384
1413394906705760512
1413394906755760384
1413394906805760512
1413394906855760384
1413394906905760512
1413394906955760384
1413394907005760512
1413394907055760384
1413394907105760512
1413394907155760384
1413394907205760512
1413394907255760384
1413394907305760512
1413394907355760384
1413394907405760512
1413394907455760384
1413394907505760512
1413394907555760384
1413394907605760512
1413394907655760384
1413394907705760512
1413394907755760384
1413394907805760512
1413394907855760384
1413394907905760512
1413394907955760384
1413394908005760512
1413394908055760384
1413394908105760512
1413394908155760384
1413394908205760512
1413394908255760384
1413394908305760512
1413394908355760384
1413394908405760512
1413394908455760384
1413394908505760512
1413394908555760384
1413394908605760512
1413394908655760384
1413394908705760512
1413394908755760384
1413394908805760512
1413394908855760384
1413394908905760512
1413394908955760384
1413394909005760512
1413394909055760384
1413394909105760512
1413394909155760384
1413394909205760512
1413394909255760384
1413394909305760512
1413394909355760384
1413394909405760512
1413394909455760384
1413394909505760512
1413394909555760384
1413394909605760512
1413394909655760384
1413394909705760512
1413394909755760384
1413394909805760512
1413394909855760384
1413394909905760512
1413394909955760384
1413394910005760512
1413394910055760384
1413394910105760512
1413394910155760384
1413394910205760512
1413394910255760384
1413394910305760512
1413394910355760384
1413394910405760512
1413394910455760384
1413394910505760512
1413394910555760384
1413394910605760512
1413394910655760384
1413394910705760512
1413394910755760384
1413394910805760512
1413394910855760384
1413394910905760512
1413394910955760384
1413394911005760512
1413394911055760384
1413394911105760512
1413394911155760384
1413394911205760512
1413394911255760384
1413394911305760512
1413394911355760384
1413394911405760512
1413394911455760384
1413394911505760512
1413394911555760384
1413394911605760512
1413394911655760384
1413394911705760512
1413394911755760384
1413394911805760512
1413394911855760384
1413394911905760512
1413394911955760384
1413394912005760512
1413394912055760384
1413394912105760512
1413394912155760384
1413394912205760512
1413394912255760384
1413394912305760512
1413394912355760384
1413394912405760512
1413394912455760384
1413394912505760512
1413394912555760384
1413394912605760512
1413394912655760384
1413394912705760512
1413394912755760384
1413394912805760512
1413394912855760384
1413394912905760512
1413394912955760384
1413394913005760512
1413394913055760384
1413394913105760512
1413394913155760384
1413394913205760512
1413394913255760384
1413394913305760512
1413394913355760384
1413394913405760512
1413394913455760384
1413394913505760512
1413394913555760384
1413394913605760512
1413394913655760384
1413394913705760512
1413394913755760384
1413394913805760512
1413394913855760384
1413394913905760512
1413394913955760384
1413394914005760512
1413394914055760384
1413394914105760512
1413394914155760384
1413394914205760512
1413394914255760384
1413394914305760512
1413394914355760384
1413394914405760512
1413394914455760384
1413394914505760512
1413394914555760384
1413394914605760512
1413394914655760384
1413394914705760512
1413394914755760384
1413394914805760512
1413394914855760384
1413394914905760512
1413394914955760384
1413394915005760512
1413394915055760384
1413394915105760512
1413394915155760384
1413394915205760512
1413394915255760384
1413394915305760512
1413394915355760384
1413394915405760512
1413394915455760384
1413394915505760512
1413394915555760384
1413394915605760512
1413394915655760384
1413394915705760512
1413394915755760384
1413394915805760512
1413394915855760384
1413394915905760512
1413394915955760384
1413394916005760512
1413394916055760384
1413394916105760512
1413394916155760384
1413394916205760512
1413394916255760384
1413394916305760512
1413394916355760384
1413394916405760512
1413394916455760384
1413394916505760512
1413394916555760384
1413394916605760512
1413394916655760384
1413394916705760512
1413394916755760384
1413394916855760384
1413394916955760384
1413394917055760384
1413394917155760384
1413394917255760384
1413394917355760384
1413394917455760384
1413394917555760384
1413394917655760384
1413394917755760384
1413394917855760384
1413394917955760384
1413394918055760384
1413394918155760384
1413394918255760384
1413394918355760384
1413394918455760384
1413394918555760384
1413394918655760384
1413394918755760384
1413394918855760384
1413394918955760384
1413394919055760384
1413394919155760384
1413394919255760384
1413394919355760384
1413394919455760384
1413394919555760384
1413394919655760384
1413394919755760384
1413394919855760384
1413394919955760384
1413394920055760384
1413394920155760384
1413394920255760384
1413394920355760384
1413394920455760384
1413394920555760384
1413394920655760384
1413394920755760384
1413394920855760384
1413394920955760384
1413394921055760384
1413394921155760384
1413394921255760384
1413394921355760384
1413394921455760384
1413394921555760384
1413394921655760384
1413394921755760384
1413394921855760384
1413394921955760384
1413394922055760384
1413394922155760384
1413394922255760384
1413394922355760384
1413394922455760384
1413394922555760384
1413394922655760384
1413394922755760384
1413394922855760384
1413394922955760384
1413394923055760384
1413394923155760384
1413394923255760384
1413394923355760384
1413394923455760384
1413394923555760384
1413394923655760384
1413394923755760384
1413394923855760384
1413394923955760384
1413394924055760384
1413394924155760384
1413394924255760384
1413394924355760384
1413394924455760384
1413394924555760384
1413394924655760384
1413394924755760384
1413394924855760384
1413394924905760512
1413394924955760384
1413394925005760512
1413394925055760384
1413394925105760512
1413394925155760384
1413394925205760512
1413394925255760384
1413394925305760512
1413394925355760384
1413394925405760512
1413394925455760384
1413394925505760512
1413394925555760384
1413394925605760512
1413394925655760384
1413394925705760512
1413394925755760384
1413394925805760512
1413394925855760384
1413394925905760512
1413394925955760384
1413394926005760512
1413394926055760384
1413394926105760512
1413394926155760384
1413394926205760512
1413394926255760384
1413394926305760512
1413394926355760384
1413394926405760512
1413394926455760384
1413394926505760512
1413394926555760384
1413394926605760512
1413394926655760384
1413394926705760512
1413394926755760384
1413394926805760512
1413394926855760384
1413394926905760512
1413394926955760384
1413394927005760512
1413394927055760384
1413394927105760512
1413394927155760384
1413394927205760512
1413394927255760384
1413394927305760512
1413394927355760384
1413394927405760512
1413394927455760384
1413394927505760512
1413394927555760384
1413394927605760512
1413394927655760384
1413394927705760512
1413394927755760384
1413394927805760512
1413394927855760384
1413394927905760512
1413394927955760384
1413394928005760512
1413394928055760384
1413394928105760512
1413394928155760384
1413394928205760512
1413394928255760384
1413394928305760512
1413394928355760384
1413394928405760512
1413394928455760384
1413394928505760512
1413394928555760384
1413394928605760512
1413394928655760384
1413394928705760512
1413394928755760384
1413394928805760512
1413394928855760384
1413394928905760512
1413394928955760384
1413394929005760512
1413394929055760384
1413394929105760512
1413394929155760384
1413394929205760512
1413394929255760384
1413394929305760512
1413394929355760384
1413394929405760512
1413394929455760384
1413394929505760512
1413394929555760384
1413394929605760512
1413394929655760384
1413394929705760512
1413394929755760384
1413394929805760512
1413394929855760384
1413394929905760512
1413394929955760384
1413394930005760512
1413394930055760384
1413394930105760512
1413394930155760384
1413394930205760512
1413394930255760384
1413394930305760512
1413394930355760384
1413394930405760512
1413394930455760384
1413394930505760512
1413394930555760384
1413394930605760512
1413394930655760384
1413394930705760512
1413394930755760384
1413394930805760512
1413394930855760384
1413394930905760512
1413394930955760384
1413394931005760512
1413394931055760384
1413394931105760512
1413394931155760384
1413394931205760512
1413394931255760384
1413394931305760512
1413394931355760384
1413394931405760512
1413394931455760384
1413394931505760512
1413394931555760384
1413394931605760512
1413394931655760384
1413394931705760512
1413394931755760384
1413394931805760512
1413394931855760384
1413394931905760512
1413394931955760384
1413394932005760512
1413394932055760384
1413394932105760512
1413394932155760384
1413394932205760512
1413394932255760384
1413394932305760512
1413394932355760384
1413394932405760512
1413394932455760384
1413394932505760512
1413394932555760384
1413394932605760512
1413394932655760384
1413394932705760512
1413394932755760384
1413394932805760512
1413394932855760384
1413394932905760512
1413394932955760384
1413394933005760512
1413394933055760384
1413394933105760512
1413394933155760384
1413394933205760512
1413394933255760384
1413394933305760512
1413394933355760384
1413394933405760512
1413394933455760384
1413394933505760512
1413394933555760384
1413394933605760512
1413394933655760384
1413394933705760512
1413394933755760384
1413394933805760512
1413394933855760384
1413394933905760512
1413394933955760384
1413394934005760512
1413394934055760384
1413394934105760512
1413394934155760384
1413394934205760512
1413394934255760384
1413394934305760512
1413394934355760384
1413394934405760512
1413394934455760384
1413394934505760512
1413394934555760384
1413394934605760512
1413394934655760384
1413394934705760512
1413394934755760384
1413394934805760512
1413394934855760384
1413394934905760512
1413394934955760384
1413394935005760512
1413394935055760384
1413394935105760512
1413394935155760384
1413394935205760512
1413394935255760384
1413394935305760512
1413394935355760384
1413394935405760512
1413394935455760384
1413394935505760512
1413394935555760384
1413394935605760512
1413394935655760384
1413394935705760512
1413394935755760384
1413394935805760512
1413394935855760384
1413394935905760512
1413394935955760384
1413394936005760512
1413394936055760384
1413394936105760512
1413394936205760512
1413394936255760384
1413394936305760512
1413394936405760512
1413394936505760512
1413394936605760512
1413394936705760512
1413394936805760512
1413394936905760512
1413394937005760512
1413394937105760512
1413394937205760512
1413394937255760384
1413394937305760512
1413394937355760384
1413394937455760384
1413394937555760384
1413394937655760384
1413394937755760384
1413394937855760384
1413394937955760384
1413394938055760384
1413394938155760384
1413394938255760384
1413394938355760384
1413394938455760384
1413394938555760384
1413394938655760384
1413394938755760384
1413394938855760384
1413394938955760384
1413394939055760384
1413394939155760384
1413394939255760384
1413394939355760384
1413394939455760384
1413394939555760384
1413394939655760384
1413394939755760384
1413394939855760384
1413394939955760384
1413394940055760384
1413394940155760384
1413394940255760384
1413394940355760384
1413394940455760384
1413394940555760384
1413394940655760384
1413394940755760384
1413394940855760384
1413394940955760384
1413394941005760512
1413394941055760384
1413394941105760512
1413394941205760512
1413394941305760512
1413394941405760512
1413394941505760512
1413394941605760512
1413394941705760512
1413394941755760384
1413394941805760512
1413394941855760384
1413394941905760512
1413394941955760384
1413394942005760512
1413394942055760384
1413394942105760512
1413394942155760384
1413394942205760512
1413394942255760384
1413394942305760512
1413394942355760384
1413394942405760512
1413394942455760384
1413394942505760512
1413394942555760384
1413394942605760512
1413394942655760384
1413394942705760512
1413394942755760384
1413394942805760512
1413394942855760384
1413394942905760512
1413394942955760384
1413394943005760512
1413394943055760384
1413394943105760512
1413394943155760384
1413394943205760512
1413394943255760384
1413394943305760512
1413394943355760384
1413394943405760512
1413394943455760384
1413394943505760512
1413394943555760384
1413394943605760512
1413394943655760384
1413394943705760512
1413394943755760384
1413394943805760512
1413394943855760384
1413394943905760512
1413394943955760384
1413394944005760512
1413394944055760384
1413394944105760512
1413394944155760384
1413394944205760512
1413394944255760384
1413394944305760512
1413394944355760384
1413394944405760512
1413394944455760384
1413394944505760512
1413394944555760384
1413394944605760512
1413394944655760384
1413394944705760512
1413394944755760384
1413394944805760512
1413394944855760384
1413394944905760512
1413394944955760384
1413394945005760512
1413394945055760384
1413394945105760512
1413394945155760384
1413394945205760512
1413394945255760384
1413394945305760512
1413394945355760384
1413394945405760512
1413394945455760384
1413394945505760512
1413394945555760384
1413394945605760512
1413394945655760384
1413394945705760512
1413394945755760384
1413394945805760512
1413394945855760384
1413394945905760512
1413394945955760384
1413394946005760512
1413394946055760384
1413394946155760384
1413394946205760512
1413394946255760384
1413394946355760384
1413394946455760384
1413394946555760384
1413394946655760384
1413394946755760384
1413394946855760384
1413394946955760384
1413394947055760384
1413394947155760384
1413394947255760384
1413394947355760384
1413394947455760384
1413394947555760384
1413394947655760384
1413394947755760384
1413394947855760384
1413394947955760384
1413394948055760384
1413394948155760384
1413394948255760384
1413394948355760384
1413394948455760384
1413394948555760384
1413394948655760384
1413394948755760384
1413394948855760384
1413394948955760384
1413394949055760384
1413394949155760384
1413394949255760384
1413394949355760384
1413394949455760384
1413394949555760384
1413394949655760384
1413394949755760384
1413394949855760384
1413394949955760384
1413394950055760384
1413394950155760384
1413394950255760384
1413394950355760384
1413394950455760384
1413394950555760384
1413394950655760384
1413394950755760384
1413394950855760384
1413394950955760384
1413394951055760384
1413394951155760384
1413394951255760384
1413394951355760384
1413394951455760384
1413394951555760384
1413394951655760384
1413394951755760384
1413394951855760384
1413394951955760384
1413394952055760384
1413394952155760384
1413394952255760384
1413394952355760384
1413394952455760384
1413394952555760384
1413394952655760384
1413394952755760384
1413394952855760384
1413394952955760384
1413394953055760384
1413394953155760384
1413394953255760384
1413394953355760384
1413394953455760384
1413394953555760384
1413394953655760384
1413394953755760384
1413394953855760384
1413394953955760384
1413394954055760384
1413394954155760384
1413394954255760384
1413394954355760384
1413394954455760384
1413394954555760384
1413394954655760384
1413394954755760384
1413394954855760384
1413394954955760384
1413394955055760384
1413394955155760384
1413394955255760384
1413394955355760384
1413394955455760384
1413394955555760384
1413394955655760384
1413394955755760384
1413394955855760384
1413394955905760512
1413394955955760384
1413394956005760512
1413394956105760512
1413394956205760512
1413394956305760512
1413394956405760512
1413394956505760512
1413394956605760512
1413394956655760384
1413394956705760512
1413394956755760384
1413394956805760512
1413394956855760384
1413394956905760512
1413394956955760384
1413394957005760512
1413394957055760384
1413394957105760512
1413394957155760384
1413394957205760512
1413394957255760384
1413394957305760512
1413394957355760384
1413394957405760512
1413394957455760384
1413394957505760512
1413394957555760384
1413394957605760512
1413394957655760384
1413394957705760512
1413394957755760384
1413394957805760512
1413394957855760384
1413394957905760512
1413394957955760384
1413394958005760512
1413394958055760384
1413394958105760512
1413394958155760384
1413394958205760512
1413394958255760384
1413394958305760512
1413394958355760384
1413394958405760512
1413394958455760384
1413394958505760512
1413394958555760384
1413394958605760512
1413394958655760384
1413394958705760512
1413394958755760384
1413394958805760512
1413394958855760384
1413394958905760512
1413394958955760384
1413394959005760512
1413394959055760384
1413394959105760512
1413394959155760384
1413394959205760512
1413394959255760384
1413394959305760512
1413394959355760384
1413394959405760512
1413394959455760384
1413394959505760512
1413394959555760384
1413394959605760512
1413394959655760384
1413394959705760512
1413394959755760384
1413394959805760512
1413394959855760384
1413394959905760512
1413394959955760384
1413394960005760512
1413394960055760384
1413394960105760512
1413394960155760384
1413394960205760512
1413394960255760384
1413394960305760512
1413394960355760384
1413394960405760512
1413394960455760384
1413394960505760512
1413394960555760384
1413394960605760512
1413394960655760384
1413394960705760512
1413394960755760384
1413394960805760512
1413394960855760384
1413394960905760512
1413394960955760384
1413394961005760512
1413394961055760384
1413394961105760512
1413394961155760384
1413394961205760512
1413394961255760384
1413394961305760512
1413394961355760384
1413394961405760512
1413394961455760384
1413394961505760512
1413394961555760384
1413394961605760512
1413394961655760384
1413394961705760512
1413394961755760384
1413394961805760512
1413394961855760384
1413394961905760512
1413394961955760384
1413394962005760512
1413394962055760384
1413394962105760512
1413394962155760384
1413394962205760512
1413394962255760384
1413394962305760512
1413394962355760384
1413394962405760512
1413394962455760384
1413394962505760512
1413394962555760384
1413394962605760512
1413394962655760384
1413394962705760512
1413394962755760384
1413394962805760512
1413394962855760384
1413394962905760512
1413394962955760384
1413394963005760512
1413394963055760384
1413394963105760512
1413394963155760384
1413394963205760512
1413394963255760384
1413394963305760512
1413394963355760384
1413394963405760512
1413394963455760384
1413394963505760512
1413394963555760384
1413394963605760512
1413394963655760384
1413394963705760512
1413394963755760384
1413394963805760512
1413394963855760384
1413394963905760512
1413394963955760384
1413394964005760512
1413394964055760384
1413394964105760512
1413394964155760384
1413394964205760512
1413394964255760384
1413394964305760512
1413394964355760384
1413394964405760512
1413394964455760384
1413394964505760512
1413394964555760384
1413394964605760512
1413394964655760384
1413394964705760512
1413394964755760384
1413394964805760512
1413394964855760384
1413394964905760512
1413394964955760384
1413394965005760512
1413394965055760384
1413394965105760512
1413394965155760384
1413394965205760512
1413394965255760384
1413394965305760512
1413394965355760384
1413394965405760512
1413394965455760384
1413394965505760512
1413394965555760384
1413394965605760512
1413394965655760384
1413394965705760512
1413394965755760384
1413394965805760512
1413394965855760384
1413394965905760512
1413394965955760384
1413394966005760512
1413394966055760384
1413394966105760512
1413394966155760384
1413394966205760512
1413394966255760384
1413394966305760512
1413394966355760384
1413394966405760512
1413394966455760384
1413394966505760512
1413394966555760384
1413394966605760512
1413394966655760384
1413394966705760512
1413394966755760384
1413394966805760512
1413394966855760384
1413394966905760512
1413394966955760384
1413394967005760512
1413394967055760384
1413394967105760512
1413394967155760384
1413394967205760512
1413394967255760384
1413394967305760512
1413394967355760384
1413394967405760512
1413394967455760384
1413394967505760512
1413394967555760384
1413394967605760512
1413394967655760384
1413394967705760512
1413394967755760384
1413394967805760512
1413394967855760384
1413394967905760512
1413394967955760384
1413394968005760512
1413394968055760384
1413394968105760512
1413394968155760384
1413394968205760512
1413394968255760384
1413394968305760512
1413394968355760384
1413394968405760512
1413394968455760384
1413394968505760512
1413394968555760384
1413394968605760512
1413394968655760384
1413394968705760512
1413394968755760384
1413394968805760512
1413394968855760384
1413394968905760512
1413394968955760384
1413394969005760512
1413394969055760384
1413394969155760384
1413394969255760384
1413394969355760384
1413394969455760384
1413394969555760384
1413394969655760384
1413394969755760384
1413394969855760384
1413394969955760384
1413394970055760384
1413394970155760384
1413394970255760384
1413394970355760384
1413394970455760384
1413394970555760384
1413394970655760384
1413394970755760384
1413394970855760384
1413394970955760384
1413394971055760384
1413394971155760384
1413394971255760384
1413394971355760384
1413394971455760384
1413394971555760384
1413394971655760384
1413394971755760384
1413394971855760384
1413394971955760384
1413394972055760384
1413394972155760384
1413394972255760384
1413394972355760384
1413394972455760384
1413394972555760384
1413394972655760384
1413394972755760384
1413394972855760384
1413394972955760384
1413394973005760512
1413394973055760384
1413394973105760512
1413394973155760384
1413394973205760512
1413394973255760384
1413394973305760512
1413394973355760384
1413394973405760512
1413394973455760384
1413394973505760512
1413394973555760384
1413394973605760512
1413394973655760384
1413394973705760512
1413394973755760384
1413394973805760512
1413394973855760384
1413394973905760512
1413394973955760384
1413394974005760512
1413394974055760384
1413394974105760512
1413394974155760384
1413394974205760512
1413394974255760384
1413394974305760512
1413394974355760384
1413394974405760512
1413394974455760384
1413394974505760512
1413394974555760384
1413394974605760512
1413394974655760384
1413394974705760512
1413394974755760384
1413394974805760512
1413394974855760384
1413394974905760512
1413394974955760384
1413394975005760512
1413394975055760384
1413394975105760512
1413394975155760384
1413394975205760512
1413394975255760384
1413394975305760512
1413394975355760384
1413394975405760512
1413394975455760384
1413394975505760512
1413394975555760384
1413394975605760512
1413394975655760384
1413394975755760384
1413394975805760512
1413394975855760384
1413394975955760384
1413394976055760384
1413394976155760384
1413394976255760384
1413394976355760384
1413394976455760384
1413394976505760512
1413394976605760512
1413394976705760512
1413394976755760384
1413394976805760512
1413394976855760384
1413394976905760512
1413394976955760384
1413394977005760512
1413394977105760512
1413394977155760384
1413394977205760512
1413394977305760512
1413394977405760512
1413394977505760512
1413394977605760512
1413394977705760512
1413394977805760512
1413394977905760512
1413394978005760512
1413394978105760512
1413394978155760384
1413394978205760512
1413394978255760384
1413394978305760512
1413394978355760384
1413394978405760512
1413394978455760384
1413394978505760512
1413394978555760384
1413394978605760512
1413394978655760384
1413394978705760512
1413394978755760384
1413394978805760512
1413394978855760384
1413394978905760512
1413394978955760384
1413394979005760512
1413394979055760384
1413394979105760512
1413394979155760384
1413394979205760512
1413394979255760384
1413394979305760512
1413394979355760384
1413394979405760512
1413394979455760384
1413394979505760512
1413394979555760384
1413394979605760512
1413394979655760384
1413394979705760512
1413394979755760384
1413394979805760512
1413394979855760384
1413394979905760512
1413394979955760384
1413394980005760512
1413394980055760384
1413394980105760512
1413394980155760384
1413394980205760512
1413394980255760384
1413394980305760512
1413394980355760384
1413394980405760512
1413394980455760384
1413394980505760512
1413394980555760384
1413394980605760512
1413394980655760384
1413394980705760512
1413394980755760384
1413394980805760512
1413394980855760384
1413394980905760512
1413394980955760384
1413394981005760512
1413394981055760384
1413394981105760512
1413394981155760384
1413394981205760512
1413394981255760384
1413394981305760512
1413394981355760384
1413394981405760512
1413394981455760384
1413394981505760512
1413394981555760384
1413394981605760512
1413394981655760384
1413394981705760512
1413394981755760384
1413394981805760512
1413394981855760384
1413394981905760512
1413394981955760384
1413394982005760512
1413394982055760384
1413394982105760512
1413394982155760384
1413394982205760512
1413394982255760384
1413394982305760512
1413394982355760384
1413394982405760512
1413394982455760384
1413394982505760512
1413394982555760384
1413394982605760512
1413394982655760384
1413394982705760512
1413394982755760384
1413394982805760512
1413394982855760384
1413394982905760512
1413394983005760512
1413394983105760512
1413394983205760512
1413394983305760512
1413394983405760512
1413394983505760512
1413394983605760512
1413394983705760512
1413394983805760512
1413394983905760512
1413394984005760512
1413394984105760512
1413394984205760512
1413394984305760512
1413394984405760512
1413394984505760512
1413394984605760512
1413394984705760512
1413394984805760512
1413394984905760512
1413394985005760512
1413394985105760512
1413394985205760512
1413394985305760512
1413394985405760512
1413394985505760512
1413394985605760512
1413394985705760512
1413394985805760512
1413394985905760512
1413394986005760512
1413394986105760512
1413394986205760512
1413394986305760512
1413394986405760512
1413394986505760512
1413394986605760512
1413394986705760512
1413394986805760512
1413394986905760512
1413394987005760512
1413394987105760512
1413394987205760512
1413394987305760512
1413394987405760512
1413394987505760512
1413394987605760512
1413394987705760512
1413394987805760512
1413394987905760512
1413394988005760512
1413394988105760512
1413394988205760512
1413394988305760512
1413394988405760512
1413394988505760512
1413394988605760512
1413394988705760512
1413394988805760512
1413394988905760512
1413394989005760512
1413394989105760512
1413394989205760512
1413394989305760512
1413394989405760512
1413394989505760512
1413394989605760512
1413394989705760512
1413394989805760512
1413394989905760512
1413394990005760512
1413394990105760512
1413394990155760384
1413394990205760512
1413394990255760384
1413394990355760384
1413394990405760512
1413394990455760384
1413394990505760512
1413394990555760384
1413394990605760512
1413394990655760384
1413394990705760512
1413394990755760384
1413394990805760512
1413394990855760384
1413394990905760512
1413394990955760384
1413394991005760512
1413394991055760384
1413394991105760512
1413394991155760384
1413394991205760512
1413394991255760384
1413394991305760512
1413394991355760384
1413394991405760512
1413394991455760384
1413394991505760512
1413394991555760384
1413394991605760512
1413394991655760384
1413394991705760512
1413394991755760384
1413394991805760512
1413394991855760384
1413394991905760512
1413394991955760384
1413394992005760512
1413394992055760384
1413394992105760512
1413394992155760384
1413394992205760512
1413394992255760384
1413394992305760512
1413394992355760384
1413394992405760512
1413394992455760384
1413394992505760512
1413394992555760384
1413394992605760512
1413394992655760384
1413394992705760512
1413394992755760384
1413394992805760512
1413394992855760384
1413394992905760512
1413394992955760384
1413394993005760512
1413394993055760384
1413394993105760512
1413394993155760384
1413394993205760512
1413394993255760384
1413394993305760512
1413394993355760384
1413394993405760512
1413394993455760384
1413394993505760512
1413394993555760384
1413394993605760512
1413394993655760384
1413394993705760512
1413394993755760384
1413394993805760512
1413394993855760384
1413394993905760512
1413394993955760384
1413394994005760512
1413394994055760384
1413394994105760512
1413394994155760384
1413394994205760512
1413394994305760512
1413394994405760512
1413394994505760512
1413394994605760512
1413394994705760512
1413394994805760512
1413394994905760512
1413394995005760512
1413394995105760512
1413394995205760512
1413394995305760512
1413394995405760512
1413394995505760512
1413394995605760512
1413394995705760512
1413394995805760512
1413394995905760512
1413394996005760512
1413394996105760512
1413394996205760512
1413394996305760512
1413394996405760512
1413394996505760512
1413394996605760512
1413394996705760512
1413394996805760512
1413394996905760512
1413394997005760512
1413394997105760512
1413394997205760512
1413394997305760512
1413394997405760512
1413394997505760512
1413394997605760512
1413394997705760512
1413394997805760512
1413394997905760512
1413394998005760512
1413394998105760512
1413394998205760512
1413394998305760512
================================================
FILE: Examples/Monocular/KITTI00-02.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 718.856
Camera.fy: 718.856
Camera.cx: 607.1928
Camera.cy: 185.2157
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
# Camera frames per second
Camera.fps: 10.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 2000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.1
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.15
Viewer.CameraLineWidth: 2
Viewer.ViewpointX: 0
Viewer.ViewpointY: -10
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Monocular/KITTI03.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 721.5377
Camera.fy: 721.5377
Camera.cx: 609.5593
Camera.cy: 172.854
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
# Camera frames per second
Camera.fps: 10.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 2000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.1
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.15
Viewer.CameraLineWidth: 2
Viewer.ViewpointX: 0
Viewer.ViewpointY: -10
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Monocular/KITTI04-12.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 707.0912
Camera.fy: 707.0912
Camera.cx: 601.8873
Camera.cy: 183.1104
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
# Camera frames per second
Camera.fps: 10.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 2000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.1
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.15
Viewer.CameraLineWidth: 2
Viewer.ViewpointX: 0
Viewer.ViewpointY: -10
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Monocular/TUM1.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 517.306408
Camera.fy: 516.469215
Camera.cx: 318.643040
Camera.cy: 255.313989
Camera.k1: 0.262383
Camera.k2: -0.953104
Camera.p1: -0.005358
Camera.p2: 0.002628
Camera.k3: 1.163314
# Camera frames per second
Camera.fps: 30.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/Monocular/TUM2.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 520.908620
Camera.fy: 521.007327
Camera.cx: 325.141442
Camera.cy: 249.701764
Camera.k1: 0.231222
Camera.k2: -0.784899
Camera.p1: -0.003257
Camera.p2: -0.000105
Camera.k3: 0.917205
# Camera frames per second
Camera.fps: 30.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/Monocular/TUM3.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 535.4
Camera.fy: 539.2
Camera.cx: 320.1
Camera.cy: 247.6
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
# Camera frames per second
Camera.fps: 30.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/Monocular/mono_euroc.cpp
================================================
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strImagePath, const string &strPathTimes,
vector &vstrImages, vector &vTimeStamps);
int main(int argc, char **argv)
{
if(argc != 5)
{
cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_image_folder path_to_times_file" << endl;
return 1;
}
// Retrieve paths to images
vector vstrImageFilenames;
vector vTimestamps;
LoadImages(string(argv[3]), string(argv[4]), vstrImageFilenames, vTimestamps);
int nImages = vstrImageFilenames.size();
if(nImages<=0)
{
cerr << "ERROR: Failed to load images" << endl;
return 1;
}
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(argv[1],argv[2],Jetson_SLAM::System::MONOCULAR,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
// Main loop
cv::Mat im;
for(int ni=0; ni >(t2 - t1).count();
vTimesTrack[ni]=ttrack;
// Wait to load the next frame
double T=0;
if(ni0)
T = tframe-vTimestamps[ni-1];
if(ttrack &vstrImages, vector &vTimeStamps)
{
ifstream fTimes;
fTimes.open(strPathTimes.c_str());
vTimeStamps.reserve(5000);
vstrImages.reserve(5000);
while(!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
{
stringstream ss;
ss << s;
vstrImages.push_back(strImagePath + "/" + ss.str() + ".png");
double t;
ss >> t;
vTimeStamps.push_back(t/1e9);
}
}
}
================================================
FILE: Examples/Monocular/mono_kitti.cpp
================================================
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include"System.h"
#include
using namespace std;
void LoadImages(const string &strSequence, vector &vstrImageFilenames,
vector &vTimestamps);
int main(int argc, char **argv)
{
if(argc != 4)
{
cerr << endl << "Usage: ./mono_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
return 1;
}
// Retrieve paths to images
vector vstrImageFilenames;
vector vTimestamps;
LoadImages(string(argv[3]), vstrImageFilenames, vTimestamps);
int nImages = vstrImageFilenames.size();
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(argv[1],argv[2],Jetson_SLAM::System::MONOCULAR,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
// Main loop
cv::Mat im;
for(int ni=0; ni >(t2 - t1).count();
vTimesTrack[ni]=ttrack;
// Wait to load the next frame
double T=0;
if(ni0)
T = tframe-vTimestamps[ni-1];
if(ttrack &vstrImageFilenames, vector &vTimestamps)
{
ifstream fTimes;
string strPathTimeFile = strPathToSequence + "/times.txt";
fTimes.open(strPathTimeFile.c_str());
while(!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t;
ss >> t;
vTimestamps.push_back(t);
}
}
string strPrefixLeft = strPathToSequence + "/image_0/";
const int nTimes = vTimestamps.size();
vstrImageFilenames.resize(nTimes);
for(int i=0; i
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strAssociationFilename, vector &vstrImageFilenamesRGB,
vector &vstrImageFilenamesD, vector &vTimestamps);
int main(int argc, char **argv)
{
if(argc != 4)
{
cerr << endl << "Usage: ./mono_live path_to_vocabulary path_to_settings" << endl;
return 1;
}
if(argc != 4)
{
cerr << endl << "Usage: ./stereo_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
return 1;
}
std::string str_vocab = argv[1];
std::string str_settings = argv[2];
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(str_vocab,str_settings,Jetson_SLAM::System::MONOCULAR,true);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
// Main loop
cv::Mat imRGB;
cv::VideoCapture cam(0);
int id = 0;
while(1)
{
std::stringstream idx;
idx << id++;
cam >> imRGB;
double tframe = std::time(0);// vTimestamps[ni];
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#endif
// Pass the images to the SLAM system
// cv::Mat pose = SLAM.TrackRGBD(imRGB,imD,tframe);
cv::Mat pose = SLAM.TrackMonocular(imRGB,tframe);
if(!pose.empty())
std::cout << pose << "\n";
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#endif
double ttrack= std::chrono::duration_cast >(t2 - t1).count();
usleep(10000);
}
// Stop all threads
SLAM.Shutdown();
// // Tracking time statistics
// sort(vTimesTrack.begin(),vTimesTrack.end());
// float totaltime = 0;
// for(int ni=0; ni (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strFile, vector &vstrImageFilenames,
vector &vTimestamps);
int main(int argc, char **argv)
{
if(argc != 4)
{
cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence" << endl;
return 1;
}
// Retrieve paths to images
vector vstrImageFilenames;
vector vTimestamps;
string strFile = string(argv[3])+"/rgb.txt";
LoadImages(strFile, vstrImageFilenames, vTimestamps);
int nImages = vstrImageFilenames.size();
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(argv[1],argv[2],Jetson_SLAM::System::MONOCULAR,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
// Main loop
cv::Mat im;
for(int ni=0; ni >(t2 - t1).count();
vTimesTrack[ni]=ttrack;
// Wait to load the next frame
double T=0;
if(ni0)
T = tframe-vTimestamps[ni-1];
if(ttrack &vstrImageFilenames, vector &vTimestamps)
{
ifstream f;
f.open(strFile.c_str());
// skip first three lines
string s0;
getline(f,s0);
getline(f,s0);
getline(f,s0);
while(!f.eof())
{
string s;
getline(f,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t;
string sRGB;
ss >> t;
vTimestamps.push_back(t);
ss >> sRGB;
vstrImageFilenames.push_back(sRGB);
}
}
}
================================================
FILE: Examples/RGB-D/TUM1.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 517.306408
Camera.fy: 516.469215
Camera.cx: 318.643040
Camera.cy: 255.313989
Camera.k1: 0.262383
Camera.k2: -0.953104
Camera.p1: -0.005358
Camera.p2: 0.002628
Camera.k3: 1.163314
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30.0
# IR projector baseline times fx (aprox.)
Camera.bf: 40.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40.0
# Deptmap values factor
DepthMapFactor: 5000.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/RGB-D/TUM1_GPU.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# GPU Parameters
#--------------------------------------------------------------------------------------------
gpu.use_gpu: 1
gpu.is_jetson: 0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 517.306408
Camera.fy: 516.469215
Camera.cx: 318.643040
Camera.cy: 255.313989
Camera.k1: 0.262383
Camera.k2: -0.953104
Camera.p1: -0.005358
Camera.p2: 0.002628
Camera.k3: 1.163314
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30.0
# IR projector baseline times fx (aprox.)
Camera.bf: 40.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40.0
# Deptmap values factor
DepthMapFactor: 5000.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
ORBextractor.tile_h: 15
ORBextractor.tile_w: 15
ORBextractor.fixed_multi_scale_tile_size: 0
ORBextractor.apply_nms_ms: 0
ORBextractor.nms_ms_mode_gpu: 1
ORBextractor.scaleFactor: 1.2
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Firstly we impose th_FAST_MAX. If no corners are detected we impose a lower value th_FAST_MIN
# You can lower these values if your images have low contrast
ORBextractor.th_FAST_MIN: 7
ORBextractor.th_FAST_MAX: 20
ORBextractor.FAST_N_MIN: 9
ORBextractor.FAST_N_MAX: 14
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/RGB-D/TUM2.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 520.908620
Camera.fy: 521.007327
Camera.cx: 325.141442
Camera.cy: 249.701764
Camera.k1: 0.231222
Camera.k2: -0.784899
Camera.p1: -0.003257
Camera.p2: -0.000105
Camera.k3: 0.917205
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30.0
# IR projector baseline times fx (aprox.)
Camera.bf: 40.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40.0
# Deptmap values factor
DepthMapFactor: 5208.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/RGB-D/TUM3.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 535.4
Camera.fy: 539.2
Camera.cx: 320.1
Camera.cy: 247.6
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30.0
# IR projector baseline times fx (aprox.)
Camera.bf: 40.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40.0
# Deptmap values factor
DepthMapFactor: 5000.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/RGB-D/associations/fr1_desk.txt
================================================
1305031453.359684 rgb/1305031453.359684.png 1305031453.374112 depth/1305031453.374112.png
1305031453.391690 rgb/1305031453.391690.png 1305031453.404816 depth/1305031453.404816.png
1305031453.423683 rgb/1305031453.423683.png 1305031453.436941 depth/1305031453.436941.png
1305031453.459685 rgb/1305031453.459685.png 1305031453.473352 depth/1305031453.473352.png
1305031453.491698 rgb/1305031453.491698.png 1305031453.505218 depth/1305031453.505218.png
1305031453.523684 rgb/1305031453.523684.png 1305031453.538301 depth/1305031453.538301.png
1305031453.559753 rgb/1305031453.559753.png 1305031453.574074 depth/1305031453.574074.png
1305031453.591640 rgb/1305031453.591640.png 1305031453.605314 depth/1305031453.605314.png
1305031453.627706 rgb/1305031453.627706.png 1305031453.636951 depth/1305031453.636951.png
1305031453.659600 rgb/1305031453.659600.png 1305031453.673185 depth/1305031453.673185.png
1305031453.691678 rgb/1305031453.691678.png 1305031453.705487 depth/1305031453.705487.png
1305031453.727652 rgb/1305031453.727652.png 1305031453.736856 depth/1305031453.736856.png
1305031453.759694 rgb/1305031453.759694.png 1305031453.773786 depth/1305031453.773786.png
1305031453.791716 rgb/1305031453.791716.png 1305031453.805041 depth/1305031453.805041.png
1305031453.827773 rgb/1305031453.827773.png 1305031453.840352 depth/1305031453.840352.png
1305031453.859705 rgb/1305031453.859705.png 1305031453.869618 depth/1305031453.869618.png
1305031453.891710 rgb/1305031453.891710.png 1305031453.905519 depth/1305031453.905519.png
1305031453.927723 rgb/1305031453.927723.png 1305031453.940012 depth/1305031453.940012.png
1305031453.959641 rgb/1305031453.959641.png 1305031453.972592 depth/1305031453.972592.png
1305031453.991624 rgb/1305031453.991624.png 1305031454.003179 depth/1305031454.003179.png
1305031454.027662 rgb/1305031454.027662.png 1305031454.040976 depth/1305031454.040976.png
1305031454.059654 rgb/1305031454.059654.png 1305031454.072690 depth/1305031454.072690.png
1305031454.091651 rgb/1305031454.091651.png 1305031454.104619 depth/1305031454.104619.png
1305031454.127701 rgb/1305031454.127701.png 1305031454.141030 depth/1305031454.141030.png
1305031454.159672 rgb/1305031454.159672.png 1305031454.172688 depth/1305031454.172688.png
1305031454.191658 rgb/1305031454.191658.png 1305031454.204626 depth/1305031454.204626.png
1305031454.227671 rgb/1305031454.227671.png 1305031454.240858 depth/1305031454.240858.png
1305031454.259627 rgb/1305031454.259627.png 1305031454.273489 depth/1305031454.273489.png
1305031454.291639 rgb/1305031454.291639.png 1305031454.304744 depth/1305031454.304744.png
1305031454.327699 rgb/1305031454.327699.png 1305031454.340806 depth/1305031454.340806.png
1305031454.359636 rgb/1305031454.359636.png 1305031454.372652 depth/1305031454.372652.png
1305031454.391677 rgb/1305031454.391677.png 1305031454.401962 depth/1305031454.401962.png
1305031454.427465 rgb/1305031454.427465.png 1305031454.437248 depth/1305031454.437248.png
1305031454.459913 rgb/1305031454.459913.png 1305031454.470741 depth/1305031454.470741.png
1305031454.491617 rgb/1305031454.491617.png 1305031454.503859 depth/1305031454.503859.png
1305031454.527700 rgb/1305031454.527700.png 1305031454.538424 depth/1305031454.538424.png
1305031454.559575 rgb/1305031454.559575.png 1305031454.570323 depth/1305031454.570323.png
1305031454.591635 rgb/1305031454.591635.png 1305031454.602019 depth/1305031454.602019.png
1305031454.627580 rgb/1305031454.627580.png 1305031454.639284 depth/1305031454.639284.png
1305031454.659528 rgb/1305031454.659528.png 1305031454.669573 depth/1305031454.669573.png
1305031454.691884 rgb/1305031454.691884.png 1305031454.702030 depth/1305031454.702030.png
1305031454.727659 rgb/1305031454.727659.png 1305031454.740764 depth/1305031454.740764.png
1305031454.759732 rgb/1305031454.759732.png 1305031454.772865 depth/1305031454.772865.png
1305031454.791641 rgb/1305031454.791641.png 1305031454.802574 depth/1305031454.802574.png
1305031454.827570 rgb/1305031454.827570.png 1305031454.840500 depth/1305031454.840500.png
1305031454.859620 rgb/1305031454.859620.png 1305031454.870269 depth/1305031454.870269.png
1305031454.891764 rgb/1305031454.891764.png 1305031454.901065 depth/1305031454.901065.png
1305031454.927567 rgb/1305031454.927567.png 1305031454.940240 depth/1305031454.940240.png
1305031454.959648 rgb/1305031454.959648.png 1305031454.973081 depth/1305031454.973081.png
1305031454.991937 rgb/1305031454.991937.png 1305031455.010759 depth/1305031455.010759.png
1305031455.027799 rgb/1305031455.027799.png 1305031455.040446 depth/1305031455.040446.png
1305031455.059636 rgb/1305031455.059636.png 1305031455.074282 depth/1305031455.074282.png
1305031455.091700 rgb/1305031455.091700.png 1305031455.110340 depth/1305031455.110340.png
1305031455.127695 rgb/1305031455.127695.png 1305031455.142700 depth/1305031455.142700.png
1305031455.159720 rgb/1305031455.159720.png 1305031455.172771 depth/1305031455.172771.png
1305031455.191655 rgb/1305031455.191655.png 1305031455.210307 depth/1305031455.210307.png
1305031455.227581 rgb/1305031455.227581.png 1305031455.240960 depth/1305031455.240960.png
1305031455.259631 rgb/1305031455.259631.png 1305031455.273001 depth/1305031455.273001.png
1305031455.291831 rgb/1305031455.291831.png 1305031455.310303 depth/1305031455.310303.png
1305031455.327766 rgb/1305031455.327766.png 1305031455.342381 depth/1305031455.342381.png
1305031455.359630 rgb/1305031455.359630.png 1305031455.374120 depth/1305031455.374120.png
1305031455.391665 rgb/1305031455.391665.png 1305031455.409213 depth/1305031455.409213.png
1305031455.427642 rgb/1305031455.427642.png 1305031455.442380 depth/1305031455.442380.png
1305031455.459589 rgb/1305031455.459589.png 1305031455.473168 depth/1305031455.473168.png
1305031455.491637 rgb/1305031455.491637.png 1305031455.509397 depth/1305031455.509397.png
1305031455.527610 rgb/1305031455.527610.png 1305031455.540835 depth/1305031455.540835.png
1305031455.559669 rgb/1305031455.559669.png 1305031455.572996 depth/1305031455.572996.png
1305031455.591645 rgb/1305031455.591645.png 1305031455.608802 depth/1305031455.608802.png
1305031455.627617 rgb/1305031455.627617.png 1305031455.641333 depth/1305031455.641333.png
1305031455.659615 rgb/1305031455.659615.png 1305031455.672887 depth/1305031455.672887.png
1305031455.691605 rgb/1305031455.691605.png 1305031455.707680 depth/1305031455.707680.png
1305031455.727628 rgb/1305031455.727628.png 1305031455.742005 depth/1305031455.742005.png
1305031455.759683 rgb/1305031455.759683.png 1305031455.773667 depth/1305031455.773667.png
1305031455.791666 rgb/1305031455.791666.png 1305031455.809109 depth/1305031455.809109.png
1305031455.827590 rgb/1305031455.827590.png 1305031455.838364 depth/1305031455.838364.png
1305031455.859526 rgb/1305031455.859526.png 1305031455.872220 depth/1305031455.872220.png
1305031455.891657 rgb/1305031455.891657.png 1305031455.908418 depth/1305031455.908418.png
1305031455.927955 rgb/1305031455.927955.png 1305031455.939606 depth/1305031455.939606.png
1305031455.959716 rgb/1305031455.959716.png 1305031455.973594 depth/1305031455.973594.png
1305031455.991694 rgb/1305031455.991694.png 1305031456.008998 depth/1305031456.008998.png
1305031456.027770 rgb/1305031456.027770.png 1305031456.041930 depth/1305031456.041930.png
1305031456.059713 rgb/1305031456.059713.png 1305031456.073846 depth/1305031456.073846.png
1305031456.091707 rgb/1305031456.091707.png 1305031456.108963 depth/1305031456.108963.png
1305031456.127645 rgb/1305031456.127645.png 1305031456.140836 depth/1305031456.140836.png
1305031456.159731 rgb/1305031456.159731.png 1305031456.173198 depth/1305031456.173198.png
1305031456.191658 rgb/1305031456.191658.png 1305031456.208934 depth/1305031456.208934.png
1305031456.227678 rgb/1305031456.227678.png 1305031456.240996 depth/1305031456.240996.png
1305031456.291675 rgb/1305031456.291675.png 1305031456.277928 depth/1305031456.277928.png
1305031456.327718 rgb/1305031456.327718.png 1305031456.341659 depth/1305031456.341659.png
1305031456.391619 rgb/1305031456.391619.png 1305031456.377115 depth/1305031456.377115.png
1305031456.427662 rgb/1305031456.427662.png 1305031456.440717 depth/1305031456.440717.png
1305031456.491677 rgb/1305031456.491677.png 1305031456.476027 depth/1305031456.476027.png
1305031456.527641 rgb/1305031456.527641.png 1305031456.541832 depth/1305031456.541832.png
1305031456.591651 rgb/1305031456.591651.png 1305031456.576087 depth/1305031456.576087.png
1305031456.627612 rgb/1305031456.627612.png 1305031456.640699 depth/1305031456.640699.png
1305031456.691612 rgb/1305031456.691612.png 1305031456.675835 depth/1305031456.675835.png
1305031456.727693 rgb/1305031456.727693.png 1305031456.740863 depth/1305031456.740863.png
1305031456.791649 rgb/1305031456.791649.png 1305031456.777218 depth/1305031456.777218.png
1305031456.827603 rgb/1305031456.827603.png 1305031456.841050 depth/1305031456.841050.png
1305031456.891672 rgb/1305031456.891672.png 1305031456.878006 depth/1305031456.878006.png
1305031456.927690 rgb/1305031456.927690.png 1305031456.942298 depth/1305031456.942298.png
1305031456.959667 rgb/1305031456.959667.png 1305031456.977139 depth/1305031456.977139.png
1305031456.991709 rgb/1305031456.991709.png 1305031457.006193 depth/1305031457.006193.png
1305031457.027648 rgb/1305031457.027648.png 1305031457.042512 depth/1305031457.042512.png
1305031457.091655 rgb/1305031457.091655.png 1305031457.076011 depth/1305031457.076011.png
1305031457.127632 rgb/1305031457.127632.png 1305031457.142120 depth/1305031457.142120.png
1305031457.191735 rgb/1305031457.191735.png 1305031457.177463 depth/1305031457.177463.png
1305031457.227543 rgb/1305031457.227543.png 1305031457.240792 depth/1305031457.240792.png
1305031457.291656 rgb/1305031457.291656.png 1305031457.277247 depth/1305031457.277247.png
1305031457.327548 rgb/1305031457.327548.png 1305031457.342954 depth/1305031457.342954.png
1305031457.391684 rgb/1305031457.391684.png 1305031457.376037 depth/1305031457.376037.png
1305031457.427641 rgb/1305031457.427641.png 1305031457.441357 depth/1305031457.441357.png
1305031457.491705 rgb/1305031457.491705.png 1305031457.476577 depth/1305031457.476577.png
1305031457.527638 rgb/1305031457.527638.png 1305031457.508603 depth/1305031457.508603.png
1305031457.559685 rgb/1305031457.559685.png 1305031457.543946 depth/1305031457.543946.png
1305031457.591678 rgb/1305031457.591678.png 1305031457.576581 depth/1305031457.576581.png
1305031457.627526 rgb/1305031457.627526.png 1305031457.643534 depth/1305031457.643534.png
1305031457.659632 rgb/1305031457.659632.png 1305031457.675414 depth/1305031457.675414.png
1305031457.691570 rgb/1305031457.691570.png 1305031457.707739 depth/1305031457.707739.png
1305031457.727669 rgb/1305031457.727669.png 1305031457.745071 depth/1305031457.745071.png
1305031457.759556 rgb/1305031457.759556.png 1305031457.773518 depth/1305031457.773518.png
1305031457.791567 rgb/1305031457.791567.png 1305031457.807824 depth/1305031457.807824.png
1305031457.827699 rgb/1305031457.827699.png 1305031457.842853 depth/1305031457.842853.png
1305031457.859623 rgb/1305031457.859623.png 1305031457.875920 depth/1305031457.875920.png
1305031457.891593 rgb/1305031457.891593.png 1305031457.906126 depth/1305031457.906126.png
1305031457.927633 rgb/1305031457.927633.png 1305031457.942604 depth/1305031457.942604.png
1305031457.991644 rgb/1305031457.991644.png 1305031457.976744 depth/1305031457.976744.png
1305031458.027845 rgb/1305031458.027845.png 1305031458.009019 depth/1305031458.009019.png
1305031458.059689 rgb/1305031458.059689.png 1305031458.046303 depth/1305031458.046303.png
1305031458.091690 rgb/1305031458.091690.png 1305031458.077315 depth/1305031458.077315.png
1305031458.127605 rgb/1305031458.127605.png 1305031458.108896 depth/1305031458.108896.png
1305031458.159638 rgb/1305031458.159638.png 1305031458.144808 depth/1305031458.144808.png
1305031458.191646 rgb/1305031458.191646.png 1305031458.178039 depth/1305031458.178039.png
1305031458.227611 rgb/1305031458.227611.png 1305031458.209384 depth/1305031458.209384.png
1305031458.259934 rgb/1305031458.259934.png 1305031458.245729 depth/1305031458.245729.png
1305031458.291664 rgb/1305031458.291664.png 1305031458.277447 depth/1305031458.277447.png
1305031458.327628 rgb/1305031458.327628.png 1305031458.308343 depth/1305031458.308343.png
1305031458.359590 rgb/1305031458.359590.png 1305031458.343898 depth/1305031458.343898.png
1305031458.391626 rgb/1305031458.391626.png 1305031458.376213 depth/1305031458.376213.png
1305031458.427598 rgb/1305031458.427598.png 1305031458.407856 depth/1305031458.407856.png
1305031458.459637 rgb/1305031458.459637.png 1305031458.443957 depth/1305031458.443957.png
1305031458.491696 rgb/1305031458.491696.png 1305031458.476034 depth/1305031458.476034.png
1305031458.527737 rgb/1305031458.527737.png 1305031458.508869 depth/1305031458.508869.png
1305031458.559628 rgb/1305031458.559628.png 1305031458.544401 depth/1305031458.544401.png
1305031458.591641 rgb/1305031458.591641.png 1305031458.576178 depth/1305031458.576178.png
1305031458.627659 rgb/1305031458.627659.png 1305031458.608421 depth/1305031458.608421.png
1305031458.659623 rgb/1305031458.659623.png 1305031458.643659 depth/1305031458.643659.png
1305031458.691674 rgb/1305031458.691674.png 1305031458.676991 depth/1305031458.676991.png
1305031458.727650 rgb/1305031458.727650.png 1305031458.744924 depth/1305031458.744924.png
1305031458.759945 rgb/1305031458.759945.png 1305031458.773802 depth/1305031458.773802.png
1305031458.791632 rgb/1305031458.791632.png 1305031458.810621 depth/1305031458.810621.png
1305031458.827564 rgb/1305031458.827564.png 1305031458.842919 depth/1305031458.842919.png
1305031458.891665 rgb/1305031458.891665.png 1305031458.875889 depth/1305031458.875889.png
1305031458.927621 rgb/1305031458.927621.png 1305031458.910599 depth/1305031458.910599.png
1305031458.959617 rgb/1305031458.959617.png 1305031458.943997 depth/1305031458.943997.png
1305031458.991647 rgb/1305031458.991647.png 1305031458.976007 depth/1305031458.976007.png
1305031459.027665 rgb/1305031459.027665.png 1305031459.012560 depth/1305031459.012560.png
1305031459.059631 rgb/1305031459.059631.png 1305031459.073657 depth/1305031459.073657.png
1305031459.127618 rgb/1305031459.127618.png 1305031459.112711 depth/1305031459.112711.png
1305031459.159639 rgb/1305031459.159639.png 1305031459.144497 depth/1305031459.144497.png
1305031459.191674 rgb/1305031459.191674.png 1305031459.176463 depth/1305031459.176463.png
1305031459.227607 rgb/1305031459.227607.png 1305031459.244159 depth/1305031459.244159.png
1305031459.259760 rgb/1305031459.259760.png 1305031459.274941 depth/1305031459.274941.png
1305031459.327632 rgb/1305031459.327632.png 1305031459.311921 depth/1305031459.311921.png
1305031459.359651 rgb/1305031459.359651.png 1305031459.374084 depth/1305031459.374084.png
1305031459.391667 rgb/1305031459.391667.png 1305031459.408831 depth/1305031459.408831.png
1305031459.427646 rgb/1305031459.427646.png 1305031459.443181 depth/1305031459.443181.png
1305031459.459679 rgb/1305031459.459679.png 1305031459.473401 depth/1305031459.473401.png
1305031459.527594 rgb/1305031459.527594.png 1305031459.510267 depth/1305031459.510267.png
1305031459.559647 rgb/1305031459.559647.png 1305031459.544431 depth/1305031459.544431.png
1305031459.591695 rgb/1305031459.591695.png 1305031459.576817 depth/1305031459.576817.png
1305031459.627608 rgb/1305031459.627608.png 1305031459.611939 depth/1305031459.611939.png
1305031459.659641 rgb/1305031459.659641.png 1305031459.643453 depth/1305031459.643453.png
1305031459.691604 rgb/1305031459.691604.png 1305031459.675678 depth/1305031459.675678.png
1305031459.727551 rgb/1305031459.727551.png 1305031459.743425 depth/1305031459.743425.png
1305031459.791650 rgb/1305031459.791650.png 1305031459.776577 depth/1305031459.776577.png
1305031459.827664 rgb/1305031459.827664.png 1305031459.812562 depth/1305031459.812562.png
1305031459.859660 rgb/1305031459.859660.png 1305031459.844736 depth/1305031459.844736.png
1305031459.891596 rgb/1305031459.891596.png 1305031459.877006 depth/1305031459.877006.png
1305031459.927607 rgb/1305031459.927607.png 1305031459.943616 depth/1305031459.943616.png
1305031459.991725 rgb/1305031459.991725.png 1305031459.979430 depth/1305031459.979430.png
1305031460.027565 rgb/1305031460.027565.png 1305031460.011909 depth/1305031460.011909.png
1305031460.059659 rgb/1305031460.059659.png 1305031460.043717 depth/1305031460.043717.png
1305031460.091717 rgb/1305031460.091717.png 1305031460.079449 depth/1305031460.079449.png
1305031460.127690 rgb/1305031460.127690.png 1305031460.111951 depth/1305031460.111951.png
1305031460.159678 rgb/1305031460.159678.png 1305031460.144204 depth/1305031460.144204.png
1305031460.191559 rgb/1305031460.191559.png 1305031460.178730 depth/1305031460.178730.png
1305031460.227761 rgb/1305031460.227761.png 1305031460.243467 depth/1305031460.243467.png
1305031460.291689 rgb/1305031460.291689.png 1305031460.279164 depth/1305031460.279164.png
1305031460.327512 rgb/1305031460.327512.png 1305031460.342879 depth/1305031460.342879.png
1305031460.391611 rgb/1305031460.391611.png 1305031460.377806 depth/1305031460.377806.png
1305031460.427477 rgb/1305031460.427477.png 1305031460.409883 depth/1305031460.409883.png
1305031460.459620 rgb/1305031460.459620.png 1305031460.444036 depth/1305031460.444036.png
1305031460.491504 rgb/1305031460.491504.png 1305031460.479856 depth/1305031460.479856.png
1305031460.527570 rgb/1305031460.527570.png 1305031460.508966 depth/1305031460.508966.png
1305031460.559647 rgb/1305031460.559647.png 1305031460.544245 depth/1305031460.544245.png
1305031460.591855 rgb/1305031460.591855.png 1305031460.579561 depth/1305031460.579561.png
1305031460.627625 rgb/1305031460.627625.png 1305031460.612190 depth/1305031460.612190.png
1305031460.659764 rgb/1305031460.659764.png 1305031460.644011 depth/1305031460.644011.png
1305031460.691671 rgb/1305031460.691671.png 1305031460.679350 depth/1305031460.679350.png
1305031460.727675 rgb/1305031460.727675.png 1305031460.711684 depth/1305031460.711684.png
1305031460.759667 rgb/1305031460.759667.png 1305031460.743767 depth/1305031460.743767.png
1305031460.791660 rgb/1305031460.791660.png 1305031460.779201 depth/1305031460.779201.png
1305031460.827660 rgb/1305031460.827660.png 1305031460.811318 depth/1305031460.811318.png
1305031460.859714 rgb/1305031460.859714.png 1305031460.843836 depth/1305031460.843836.png
1305031460.891774 rgb/1305031460.891774.png 1305031460.879093 depth/1305031460.879093.png
1305031460.927562 rgb/1305031460.927562.png 1305031460.943375 depth/1305031460.943375.png
1305031460.991668 rgb/1305031460.991668.png 1305031460.979083 depth/1305031460.979083.png
1305031461.027620 rgb/1305031461.027620.png 1305031461.043398 depth/1305031461.043398.png
1305031461.091728 rgb/1305031461.091728.png 1305031461.079602 depth/1305031461.079602.png
1305031461.127586 rgb/1305031461.127586.png 1305031461.111961 depth/1305031461.111961.png
1305031461.159720 rgb/1305031461.159720.png 1305031461.144098 depth/1305031461.144098.png
1305031461.192013 rgb/1305031461.192013.png 1305031461.179883 depth/1305031461.179883.png
1305031461.227607 rgb/1305031461.227607.png 1305031461.211180 depth/1305031461.211180.png
1305031461.259642 rgb/1305031461.259642.png 1305031461.246864 depth/1305031461.246864.png
1305031461.291656 rgb/1305031461.291656.png 1305031461.278888 depth/1305031461.278888.png
1305031461.327751 rgb/1305031461.327751.png 1305031461.311240 depth/1305031461.311240.png
1305031461.359709 rgb/1305031461.359709.png 1305031461.346875 depth/1305031461.346875.png
1305031461.391708 rgb/1305031461.391708.png 1305031461.378850 depth/1305031461.378850.png
1305031461.427624 rgb/1305031461.427624.png 1305031461.411130 depth/1305031461.411130.png
1305031461.459781 rgb/1305031461.459781.png 1305031461.447015 depth/1305031461.447015.png
1305031461.491677 rgb/1305031461.491677.png 1305031461.478901 depth/1305031461.478901.png
1305031461.527705 rgb/1305031461.527705.png 1305031461.512120 depth/1305031461.512120.png
1305031461.559677 rgb/1305031461.559677.png 1305031461.547338 depth/1305031461.547338.png
1305031461.591690 rgb/1305031461.591690.png 1305031461.578847 depth/1305031461.578847.png
1305031461.627541 rgb/1305031461.627541.png 1305031461.609662 depth/1305031461.609662.png
1305031461.659622 rgb/1305031461.659622.png 1305031461.646970 depth/1305031461.646970.png
1305031461.691563 rgb/1305031461.691563.png 1305031461.676203 depth/1305031461.676203.png
1305031461.727602 rgb/1305031461.727602.png 1305031461.711212 depth/1305031461.711212.png
1305031461.759684 rgb/1305031461.759684.png 1305031461.746919 depth/1305031461.746919.png
1305031461.791612 rgb/1305031461.791612.png 1305031461.778616 depth/1305031461.778616.png
1305031461.827615 rgb/1305031461.827615.png 1305031461.811319 depth/1305031461.811319.png
1305031461.859767 rgb/1305031461.859767.png 1305031461.847090 depth/1305031461.847090.png
1305031461.891723 rgb/1305031461.891723.png 1305031461.879162 depth/1305031461.879162.png
1305031461.927758 rgb/1305031461.927758.png 1305031461.911121 depth/1305031461.911121.png
1305031461.959703 rgb/1305031461.959703.png 1305031461.947264 depth/1305031461.947264.png
1305031461.991590 rgb/1305031461.991590.png 1305031461.979223 depth/1305031461.979223.png
1305031462.027675 rgb/1305031462.027675.png 1305031462.011791 depth/1305031462.011791.png
1305031462.059837 rgb/1305031462.059837.png 1305031462.047463 depth/1305031462.047463.png
1305031462.091777 rgb/1305031462.091777.png 1305031462.079285 depth/1305031462.079285.png
1305031462.127739 rgb/1305031462.127739.png 1305031462.112081 depth/1305031462.112081.png
1305031462.159646 rgb/1305031462.159646.png 1305031462.147634 depth/1305031462.147634.png
1305031462.191641 rgb/1305031462.191641.png 1305031462.179358 depth/1305031462.179358.png
1305031462.227633 rgb/1305031462.227633.png 1305031462.212836 depth/1305031462.212836.png
1305031462.259765 rgb/1305031462.259765.png 1305031462.248986 depth/1305031462.248986.png
1305031462.291629 rgb/1305031462.291629.png 1305031462.280774 depth/1305031462.280774.png
1305031462.327540 rgb/1305031462.327540.png 1305031462.311931 depth/1305031462.311931.png
1305031462.359732 rgb/1305031462.359732.png 1305031462.347816 depth/1305031462.347816.png
1305031462.391695 rgb/1305031462.391695.png 1305031462.379950 depth/1305031462.379950.png
1305031462.427635 rgb/1305031462.427635.png 1305031462.413016 depth/1305031462.413016.png
1305031462.459897 rgb/1305031462.459897.png 1305031462.448295 depth/1305031462.448295.png
1305031462.492008 rgb/1305031462.492008.png 1305031462.480843 depth/1305031462.480843.png
1305031462.527670 rgb/1305031462.527670.png 1305031462.517041 depth/1305031462.517041.png
1305031462.559862 rgb/1305031462.559862.png 1305031462.548959 depth/1305031462.548959.png
1305031462.591862 rgb/1305031462.591862.png 1305031462.581088 depth/1305031462.581088.png
1305031462.627851 rgb/1305031462.627851.png 1305031462.617123 depth/1305031462.617123.png
1305031462.659660 rgb/1305031462.659660.png 1305031462.648708 depth/1305031462.648708.png
1305031462.692548 rgb/1305031462.692548.png 1305031462.680788 depth/1305031462.680788.png
1305031462.727652 rgb/1305031462.727652.png 1305031462.716812 depth/1305031462.716812.png
1305031462.759782 rgb/1305031462.759782.png 1305031462.748732 depth/1305031462.748732.png
1305031462.791943 rgb/1305031462.791943.png 1305031462.780885 depth/1305031462.780885.png
1305031462.827816 rgb/1305031462.827816.png 1305031462.816821 depth/1305031462.816821.png
1305031462.859782 rgb/1305031462.859782.png 1305031462.848525 depth/1305031462.848525.png
1305031462.891847 rgb/1305031462.891847.png 1305031462.880471 depth/1305031462.880471.png
1305031462.927607 rgb/1305031462.927607.png 1305031462.916800 depth/1305031462.916800.png
1305031462.959676 rgb/1305031462.959676.png 1305031462.947939 depth/1305031462.947939.png
1305031462.995550 rgb/1305031462.995550.png 1305031462.979943 depth/1305031462.979943.png
1305031463.027667 rgb/1305031463.027667.png 1305031463.016121 depth/1305031463.016121.png
1305031463.059810 rgb/1305031463.059810.png 1305031463.050783 depth/1305031463.050783.png
1305031463.095809 rgb/1305031463.095809.png 1305031463.076870 depth/1305031463.076870.png
1305031463.127550 rgb/1305031463.127550.png 1305031463.116806 depth/1305031463.116806.png
1305031463.159787 rgb/1305031463.159787.png 1305031463.148565 depth/1305031463.148565.png
1305031463.195657 rgb/1305031463.195657.png 1305031463.180505 depth/1305031463.180505.png
1305031463.227784 rgb/1305031463.227784.png 1305031463.217123 depth/1305031463.217123.png
1305031463.260034 rgb/1305031463.260034.png 1305031463.248719 depth/1305031463.248719.png
1305031463.295737 rgb/1305031463.295737.png 1305031463.278737 depth/1305031463.278737.png
1305031463.327739 rgb/1305031463.327739.png 1305031463.317110 depth/1305031463.317110.png
1305031463.359750 rgb/1305031463.359750.png 1305031463.348740 depth/1305031463.348740.png
1305031463.395630 rgb/1305031463.395630.png 1305031463.380514 depth/1305031463.380514.png
1305031463.427716 rgb/1305031463.427716.png 1305031463.416326 depth/1305031463.416326.png
1305031463.459756 rgb/1305031463.459756.png 1305031463.444773 depth/1305031463.444773.png
1305031463.495629 rgb/1305031463.495629.png 1305031463.480415 depth/1305031463.480415.png
1305031463.527670 rgb/1305031463.527670.png 1305031463.516994 depth/1305031463.516994.png
1305031463.559751 rgb/1305031463.559751.png 1305031463.548505 depth/1305031463.548505.png
1305031463.595600 rgb/1305031463.595600.png 1305031463.580684 depth/1305031463.580684.png
1305031463.627588 rgb/1305031463.627588.png 1305031463.616671 depth/1305031463.616671.png
1305031463.659766 rgb/1305031463.659766.png 1305031463.646147 depth/1305031463.646147.png
1305031463.695640 rgb/1305031463.695640.png 1305031463.683908 depth/1305031463.683908.png
1305031463.727588 rgb/1305031463.727588.png 1305031463.716110 depth/1305031463.716110.png
1305031463.759674 rgb/1305031463.759674.png 1305031463.747849 depth/1305031463.747849.png
1305031463.795647 rgb/1305031463.795647.png 1305031463.783912 depth/1305031463.783912.png
1305031463.827761 rgb/1305031463.827761.png 1305031463.815883 depth/1305031463.815883.png
1305031463.859910 rgb/1305031463.859910.png 1305031463.848094 depth/1305031463.848094.png
1305031463.895648 rgb/1305031463.895648.png 1305031463.883817 depth/1305031463.883817.png
1305031463.927664 rgb/1305031463.927664.png 1305031463.917433 depth/1305031463.917433.png
1305031463.959680 rgb/1305031463.959680.png 1305031463.944435 depth/1305031463.944435.png
1305031463.995821 rgb/1305031463.995821.png 1305031463.983748 depth/1305031463.983748.png
1305031464.027703 rgb/1305031464.027703.png 1305031464.015867 depth/1305031464.015867.png
1305031464.059652 rgb/1305031464.059652.png 1305031464.047778 depth/1305031464.047778.png
1305031464.095634 rgb/1305031464.095634.png 1305031464.083152 depth/1305031464.083152.png
1305031464.127681 rgb/1305031464.127681.png 1305031464.115837 depth/1305031464.115837.png
1305031464.159817 rgb/1305031464.159817.png 1305031464.147663 depth/1305031464.147663.png
1305031464.195585 rgb/1305031464.195585.png 1305031464.183566 depth/1305031464.183566.png
1305031464.227624 rgb/1305031464.227624.png 1305031464.212447 depth/1305031464.212447.png
1305031464.259644 rgb/1305031464.259644.png 1305031464.247602 depth/1305031464.247602.png
1305031464.295667 rgb/1305031464.295667.png 1305031464.283694 depth/1305031464.283694.png
1305031464.327866 rgb/1305031464.327866.png 1305031464.315699 depth/1305031464.315699.png
1305031464.359684 rgb/1305031464.359684.png 1305031464.347553 depth/1305031464.347553.png
1305031464.395611 rgb/1305031464.395611.png 1305031464.383465 depth/1305031464.383465.png
1305031464.427634 rgb/1305031464.427634.png 1305031464.415539 depth/1305031464.415539.png
1305031464.459689 rgb/1305031464.459689.png 1305031464.444269 depth/1305031464.444269.png
1305031464.495633 rgb/1305031464.495633.png 1305031464.487561 depth/1305031464.487561.png
1305031464.527574 rgb/1305031464.527574.png 1305031464.513688 depth/1305031464.513688.png
1305031464.559703 rgb/1305031464.559703.png 1305031464.548007 depth/1305031464.548007.png
1305031464.595698 rgb/1305031464.595698.png 1305031464.584260 depth/1305031464.584260.png
1305031464.627672 rgb/1305031464.627672.png 1305031464.615688 depth/1305031464.615688.png
1305031464.659749 rgb/1305031464.659749.png 1305031464.648851 depth/1305031464.648851.png
1305031464.695663 rgb/1305031464.695663.png 1305031464.684318 depth/1305031464.684318.png
1305031464.727652 rgb/1305031464.727652.png 1305031464.716305 depth/1305031464.716305.png
1305031464.759740 rgb/1305031464.759740.png 1305031464.748588 depth/1305031464.748588.png
1305031464.796021 rgb/1305031464.796021.png 1305031464.784268 depth/1305031464.784268.png
1305031464.827759 rgb/1305031464.827759.png 1305031464.816195 depth/1305031464.816195.png
1305031464.859654 rgb/1305031464.859654.png 1305031464.848283 depth/1305031464.848283.png
1305031464.895817 rgb/1305031464.895817.png 1305031464.884177 depth/1305031464.884177.png
1305031464.927799 rgb/1305031464.927799.png 1305031464.916391 depth/1305031464.916391.png
1305031464.959763 rgb/1305031464.959763.png 1305031464.952471 depth/1305031464.952471.png
1305031464.995687 rgb/1305031464.995687.png 1305031464.984257 depth/1305031464.984257.png
1305031465.027823 rgb/1305031465.027823.png 1305031465.015390 depth/1305031465.015390.png
1305031465.059749 rgb/1305031465.059749.png 1305031465.048430 depth/1305031465.048430.png
1305031465.095700 rgb/1305031465.095700.png 1305031465.083338 depth/1305031465.083338.png
1305031465.127664 rgb/1305031465.127664.png 1305031465.115475 depth/1305031465.115475.png
1305031465.159842 rgb/1305031465.159842.png 1305031465.151558 depth/1305031465.151558.png
1305031465.195564 rgb/1305031465.195564.png 1305031465.183558 depth/1305031465.183558.png
1305031465.227907 rgb/1305031465.227907.png 1305031465.215832 depth/1305031465.215832.png
1305031465.259807 rgb/1305031465.259807.png 1305031465.251788 depth/1305031465.251788.png
1305031465.295623 rgb/1305031465.295623.png 1305031465.283737 depth/1305031465.283737.png
1305031465.327674 rgb/1305031465.327674.png 1305031465.315985 depth/1305031465.315985.png
1305031465.359948 rgb/1305031465.359948.png 1305031465.351729 depth/1305031465.351729.png
1305031465.395586 rgb/1305031465.395586.png 1305031465.383701 depth/1305031465.383701.png
1305031465.427697 rgb/1305031465.427697.png 1305031465.416543 depth/1305031465.416543.png
1305031465.460125 rgb/1305031465.460125.png 1305031465.452401 depth/1305031465.452401.png
1305031465.495703 rgb/1305031465.495703.png 1305031465.483803 depth/1305031465.483803.png
1305031465.527622 rgb/1305031465.527622.png 1305031465.516043 depth/1305031465.516043.png
1305031465.559812 rgb/1305031465.559812.png 1305031465.551838 depth/1305031465.551838.png
1305031465.595599 rgb/1305031465.595599.png 1305031465.583570 depth/1305031465.583570.png
1305031465.627688 rgb/1305031465.627688.png 1305031465.615685 depth/1305031465.615685.png
1305031465.660060 rgb/1305031465.660060.png 1305031465.651645 depth/1305031465.651645.png
1305031465.695668 rgb/1305031465.695668.png 1305031465.684759 depth/1305031465.684759.png
1305031465.727682 rgb/1305031465.727682.png 1305031465.716279 depth/1305031465.716279.png
1305031465.759766 rgb/1305031465.759766.png 1305031465.753153 depth/1305031465.753153.png
1305031465.795937 rgb/1305031465.795937.png 1305031465.784387 depth/1305031465.784387.png
1305031465.827996 rgb/1305031465.827996.png 1305031465.816591 depth/1305031465.816591.png
1305031465.859861 rgb/1305031465.859861.png 1305031465.852860 depth/1305031465.852860.png
1305031465.895494 rgb/1305031465.895494.png 1305031465.884370 depth/1305031465.884370.png
1305031465.927495 rgb/1305031465.927495.png 1305031465.912828 depth/1305031465.912828.png
1305031465.959710 rgb/1305031465.959710.png 1305031465.952840 depth/1305031465.952840.png
1305031465.995753 rgb/1305031465.995753.png 1305031465.984183 depth/1305031465.984183.png
1305031466.027644 rgb/1305031466.027644.png 1305031466.016599 depth/1305031466.016599.png
1305031466.059757 rgb/1305031466.059757.png 1305031466.052655 depth/1305031466.052655.png
1305031466.095840 rgb/1305031466.095840.png 1305031466.083913 depth/1305031466.083913.png
1305031466.127640 rgb/1305031466.127640.png 1305031466.116400 depth/1305031466.116400.png
1305031466.160428 rgb/1305031466.160428.png 1305031466.152540 depth/1305031466.152540.png
1305031466.195833 rgb/1305031466.195833.png 1305031466.184186 depth/1305031466.184186.png
1305031466.227951 rgb/1305031466.227951.png 1305031466.220477 depth/1305031466.220477.png
1305031466.259815 rgb/1305031466.259815.png 1305031466.252491 depth/1305031466.252491.png
1305031466.295737 rgb/1305031466.295737.png 1305031466.284389 depth/1305031466.284389.png
1305031466.327702 rgb/1305031466.327702.png 1305031466.320055 depth/1305031466.320055.png
1305031466.359829 rgb/1305031466.359829.png 1305031466.352082 depth/1305031466.352082.png
1305031466.395784 rgb/1305031466.395784.png 1305031466.384479 depth/1305031466.384479.png
1305031466.427819 rgb/1305031466.427819.png 1305031466.420844 depth/1305031466.420844.png
1305031466.459790 rgb/1305031466.459790.png 1305031466.452369 depth/1305031466.452369.png
1305031466.495809 rgb/1305031466.495809.png 1305031466.483315 depth/1305031466.483315.png
1305031466.527538 rgb/1305031466.527538.png 1305031466.519548 depth/1305031466.519548.png
1305031466.560353 rgb/1305031466.560353.png 1305031466.552219 depth/1305031466.552219.png
1305031466.595936 rgb/1305031466.595936.png 1305031466.584438 depth/1305031466.584438.png
1305031466.627549 rgb/1305031466.627549.png 1305031466.620424 depth/1305031466.620424.png
1305031466.659688 rgb/1305031466.659688.png 1305031466.648654 depth/1305031466.648654.png
1305031466.695822 rgb/1305031466.695822.png 1305031466.684412 depth/1305031466.684412.png
1305031466.728074 rgb/1305031466.728074.png 1305031466.719744 depth/1305031466.719744.png
1305031466.759637 rgb/1305031466.759637.png 1305031466.748734 depth/1305031466.748734.png
1305031466.795604 rgb/1305031466.795604.png 1305031466.784300 depth/1305031466.784300.png
1305031466.827879 rgb/1305031466.827879.png 1305031466.819502 depth/1305031466.819502.png
1305031466.859665 rgb/1305031466.859665.png 1305031466.851527 depth/1305031466.851527.png
1305031466.895694 rgb/1305031466.895694.png 1305031466.883430 depth/1305031466.883430.png
1305031466.927756 rgb/1305031466.927756.png 1305031466.919411 depth/1305031466.919411.png
1305031466.959728 rgb/1305031466.959728.png 1305031466.952451 depth/1305031466.952451.png
1305031466.995712 rgb/1305031466.995712.png 1305031466.984027 depth/1305031466.984027.png
1305031467.027843 rgb/1305031467.027843.png 1305031467.020424 depth/1305031467.020424.png
1305031467.059700 rgb/1305031467.059700.png 1305031467.052391 depth/1305031467.052391.png
1305031467.095687 rgb/1305031467.095687.png 1305031467.084130 depth/1305031467.084130.png
1305031467.128974 rgb/1305031467.128974.png 1305031467.120528 depth/1305031467.120528.png
1305031467.159660 rgb/1305031467.159660.png 1305031467.152363 depth/1305031467.152363.png
1305031467.195663 rgb/1305031467.195663.png 1305031467.184216 depth/1305031467.184216.png
1305031467.227704 rgb/1305031467.227704.png 1305031467.220466 depth/1305031467.220466.png
1305031467.259694 rgb/1305031467.259694.png 1305031467.252275 depth/1305031467.252275.png
1305031467.295846 rgb/1305031467.295846.png 1305031467.284258 depth/1305031467.284258.png
1305031467.328008 rgb/1305031467.328008.png 1305031467.318028 depth/1305031467.318028.png
1305031467.359654 rgb/1305031467.359654.png 1305031467.349355 depth/1305031467.349355.png
1305031467.395756 rgb/1305031467.395756.png 1305031467.383844 depth/1305031467.383844.png
1305031467.427783 rgb/1305031467.427783.png 1305031467.420160 depth/1305031467.420160.png
1305031467.459692 rgb/1305031467.459692.png 1305031467.452057 depth/1305031467.452057.png
1305031467.496058 rgb/1305031467.496058.png 1305031467.484357 depth/1305031467.484357.png
1305031467.527663 rgb/1305031467.527663.png 1305031467.520535 depth/1305031467.520535.png
1305031467.559763 rgb/1305031467.559763.png 1305031467.552164 depth/1305031467.552164.png
1305031467.595989 rgb/1305031467.595989.png 1305031467.584354 depth/1305031467.584354.png
1305031467.627532 rgb/1305031467.627532.png 1305031467.618680 depth/1305031467.618680.png
1305031467.659626 rgb/1305031467.659626.png 1305031467.651977 depth/1305031467.651977.png
1305031467.695886 rgb/1305031467.695886.png 1305031467.686044 depth/1305031467.686044.png
1305031467.727535 rgb/1305031467.727535.png 1305031467.718326 depth/1305031467.718326.png
1305031467.759907 rgb/1305031467.759907.png 1305031467.752580 depth/1305031467.752580.png
1305031467.796075 rgb/1305031467.796075.png 1305031467.788562 depth/1305031467.788562.png
1305031467.827800 rgb/1305031467.827800.png 1305031467.820454 depth/1305031467.820454.png
1305031467.859729 rgb/1305031467.859729.png 1305031467.852678 depth/1305031467.852678.png
1305031467.895947 rgb/1305031467.895947.png 1305031467.888472 depth/1305031467.888472.png
1305031467.927754 rgb/1305031467.927754.png 1305031467.920800 depth/1305031467.920800.png
1305031467.959826 rgb/1305031467.959826.png 1305031467.952485 depth/1305031467.952485.png
1305031467.995754 rgb/1305031467.995754.png 1305031467.988523 depth/1305031467.988523.png
1305031468.028107 rgb/1305031468.028107.png 1305031468.020491 depth/1305031468.020491.png
1305031468.059850 rgb/1305031468.059850.png 1305031468.052668 depth/1305031468.052668.png
1305031468.095867 rgb/1305031468.095867.png 1305031468.088379 depth/1305031468.088379.png
1305031468.127816 rgb/1305031468.127816.png 1305031468.120522 depth/1305031468.120522.png
1305031468.159864 rgb/1305031468.159864.png 1305031468.152356 depth/1305031468.152356.png
1305031468.195985 rgb/1305031468.195985.png 1305031468.188327 depth/1305031468.188327.png
1305031468.228158 rgb/1305031468.228158.png 1305031468.220648 depth/1305031468.220648.png
1305031468.259754 rgb/1305031468.259754.png 1305031468.252517 depth/1305031468.252517.png
1305031468.295830 rgb/1305031468.295830.png 1305031468.288361 depth/1305031468.288361.png
1305031468.327847 rgb/1305031468.327847.png 1305031468.320522 depth/1305031468.320522.png
1305031468.359787 rgb/1305031468.359787.png 1305031468.352594 depth/1305031468.352594.png
1305031468.395860 rgb/1305031468.395860.png 1305031468.384700 depth/1305031468.384700.png
1305031468.428025 rgb/1305031468.428025.png 1305031468.420595 depth/1305031468.420595.png
1305031468.459759 rgb/1305031468.459759.png 1305031468.452605 depth/1305031468.452605.png
1305031468.495809 rgb/1305031468.495809.png 1305031468.488646 depth/1305031468.488646.png
1305031468.527756 rgb/1305031468.527756.png 1305031468.520786 depth/1305031468.520786.png
1305031468.559739 rgb/1305031468.559739.png 1305031468.552701 depth/1305031468.552701.png
1305031468.595768 rgb/1305031468.595768.png 1305031468.588614 depth/1305031468.588614.png
1305031468.627626 rgb/1305031468.627626.png 1305031468.620590 depth/1305031468.620590.png
1305031468.659579 rgb/1305031468.659579.png 1305031468.656644 depth/1305031468.656644.png
1305031468.695835 rgb/1305031468.695835.png 1305031468.688643 depth/1305031468.688643.png
1305031468.727785 rgb/1305031468.727785.png 1305031468.720560 depth/1305031468.720560.png
1305031468.759628 rgb/1305031468.759628.png 1305031468.756725 depth/1305031468.756725.png
1305031468.795796 rgb/1305031468.795796.png 1305031468.788562 depth/1305031468.788562.png
1305031468.829247 rgb/1305031468.829247.png 1305031468.817997 depth/1305031468.817997.png
1305031468.859659 rgb/1305031468.859659.png 1305031468.854887 depth/1305031468.854887.png
1305031468.895873 rgb/1305031468.895873.png 1305031468.889220 depth/1305031468.889220.png
1305031468.928141 rgb/1305031468.928141.png 1305031468.920539 depth/1305031468.920539.png
1305031468.959594 rgb/1305031468.959594.png 1305031468.956482 depth/1305031468.956482.png
1305031468.995711 rgb/1305031468.995711.png 1305031468.986011 depth/1305031468.986011.png
1305031469.027699 rgb/1305031469.027699.png 1305031469.020731 depth/1305031469.020731.png
1305031469.059832 rgb/1305031469.059832.png 1305031469.056318 depth/1305031469.056318.png
1305031469.095723 rgb/1305031469.095723.png 1305031469.088069 depth/1305031469.088069.png
1305031469.127679 rgb/1305031469.127679.png 1305031469.119984 depth/1305031469.119984.png
1305031469.159703 rgb/1305031469.159703.png 1305031469.155046 depth/1305031469.155046.png
1305031469.195540 rgb/1305031469.195540.png 1305031469.184648 depth/1305031469.184648.png
1305031469.227754 rgb/1305031469.227754.png 1305031469.219541 depth/1305031469.219541.png
1305031469.259586 rgb/1305031469.259586.png 1305031469.256002 depth/1305031469.256002.png
1305031469.296754 rgb/1305031469.296754.png 1305031469.288263 depth/1305031469.288263.png
1305031469.327618 rgb/1305031469.327618.png 1305031469.319772 depth/1305031469.319772.png
1305031469.359592 rgb/1305031469.359592.png 1305031469.356116 depth/1305031469.356116.png
1305031469.395695 rgb/1305031469.395695.png 1305031469.388556 depth/1305031469.388556.png
1305031469.427651 rgb/1305031469.427651.png 1305031469.420278 depth/1305031469.420278.png
1305031469.459668 rgb/1305031469.459668.png 1305031469.456563 depth/1305031469.456563.png
1305031469.495744 rgb/1305031469.495744.png 1305031469.488520 depth/1305031469.488520.png
1305031469.527622 rgb/1305031469.527622.png 1305031469.520417 depth/1305031469.520417.png
1305031469.559645 rgb/1305031469.559645.png 1305031469.556139 depth/1305031469.556139.png
1305031469.595755 rgb/1305031469.595755.png 1305031469.588500 depth/1305031469.588500.png
1305031469.627752 rgb/1305031469.627752.png 1305031469.620563 depth/1305031469.620563.png
1305031469.659590 rgb/1305031469.659590.png 1305031469.656279 depth/1305031469.656279.png
1305031469.695613 rgb/1305031469.695613.png 1305031469.687925 depth/1305031469.687925.png
1305031469.727679 rgb/1305031469.727679.png 1305031469.718943 depth/1305031469.718943.png
1305031469.759599 rgb/1305031469.759599.png 1305031469.756754 depth/1305031469.756754.png
1305031469.795621 rgb/1305031469.795621.png 1305031469.784733 depth/1305031469.784733.png
1305031469.827526 rgb/1305031469.827526.png 1305031469.820544 depth/1305031469.820544.png
1305031469.859574 rgb/1305031469.859574.png 1305031469.854359 depth/1305031469.854359.png
1305031469.895755 rgb/1305031469.895755.png 1305031469.885343 depth/1305031469.885343.png
1305031469.927854 rgb/1305031469.927854.png 1305031469.921773 depth/1305031469.921773.png
1305031469.959805 rgb/1305031469.959805.png 1305031469.953180 depth/1305031469.953180.png
1305031469.995551 rgb/1305031469.995551.png 1305031469.985327 depth/1305031469.985327.png
1305031470.027694 rgb/1305031470.027694.png 1305031470.024714 depth/1305031470.024714.png
1305031470.059638 rgb/1305031470.059638.png 1305031470.057400 depth/1305031470.057400.png
1305031470.095944 rgb/1305031470.095944.png 1305031470.088874 depth/1305031470.088874.png
1305031470.127633 rgb/1305031470.127633.png 1305031470.124820 depth/1305031470.124820.png
1305031470.159626 rgb/1305031470.159626.png 1305031470.156744 depth/1305031470.156744.png
1305031470.196092 rgb/1305031470.196092.png 1305031470.188876 depth/1305031470.188876.png
1305031470.227618 rgb/1305031470.227618.png 1305031470.224776 depth/1305031470.224776.png
1305031470.259965 rgb/1305031470.259965.png 1305031470.253015 depth/1305031470.253015.png
1305031470.295718 rgb/1305031470.295718.png 1305031470.287867 depth/1305031470.287867.png
1305031470.327644 rgb/1305031470.327644.png 1305031470.324266 depth/1305031470.324266.png
1305031470.359624 rgb/1305031470.359624.png 1305031470.356871 depth/1305031470.356871.png
1305031470.395823 rgb/1305031470.395823.png 1305031470.388056 depth/1305031470.388056.png
1305031470.427641 rgb/1305031470.427641.png 1305031470.424090 depth/1305031470.424090.png
1305031470.459721 rgb/1305031470.459721.png 1305031470.455875 depth/1305031470.455875.png
1305031470.495686 rgb/1305031470.495686.png 1305031470.487958 depth/1305031470.487958.png
1305031470.527689 rgb/1305031470.527689.png 1305031470.524431 depth/1305031470.524431.png
1305031470.559677 rgb/1305031470.559677.png 1305031470.556484 depth/1305031470.556484.png
1305031470.595760 rgb/1305031470.595760.png 1305031470.588797 depth/1305031470.588797.png
1305031470.627729 rgb/1305031470.627729.png 1305031470.624535 depth/1305031470.624535.png
1305031470.659690 rgb/1305031470.659690.png 1305031470.656787 depth/1305031470.656787.png
1305031470.695630 rgb/1305031470.695630.png 1305031470.688640 depth/1305031470.688640.png
1305031470.727654 rgb/1305031470.727654.png 1305031470.724461 depth/1305031470.724461.png
1305031470.759682 rgb/1305031470.759682.png 1305031470.755944 depth/1305031470.755944.png
1305031470.795615 rgb/1305031470.795615.png 1305031470.788407 depth/1305031470.788407.png
1305031470.827831 rgb/1305031470.827831.png 1305031470.820633 depth/1305031470.820633.png
1305031470.859645 rgb/1305031470.859645.png 1305031470.855509 depth/1305031470.855509.png
1305031470.895722 rgb/1305031470.895722.png 1305031470.886079 depth/1305031470.886079.png
1305031470.927684 rgb/1305031470.927684.png 1305031470.924410 depth/1305031470.924410.png
1305031470.959647 rgb/1305031470.959647.png 1305031470.956439 depth/1305031470.956439.png
1305031470.995996 rgb/1305031470.995996.png 1305031470.988276 depth/1305031470.988276.png
1305031471.027644 rgb/1305031471.027644.png 1305031471.024309 depth/1305031471.024309.png
1305031471.059636 rgb/1305031471.059636.png 1305031471.056616 depth/1305031471.056616.png
1305031471.095777 rgb/1305031471.095777.png 1305031471.088440 depth/1305031471.088440.png
1305031471.127663 rgb/1305031471.127663.png 1305031471.123837 depth/1305031471.123837.png
1305031471.159649 rgb/1305031471.159649.png 1305031471.155886 depth/1305031471.155886.png
1305031471.195703 rgb/1305031471.195703.png 1305031471.192698 depth/1305031471.192698.png
1305031471.227569 rgb/1305031471.227569.png 1305031471.224404 depth/1305031471.224404.png
1305031471.259722 rgb/1305031471.259722.png 1305031471.256397 depth/1305031471.256397.png
1305031471.296068 rgb/1305031471.296068.png 1305031471.288603 depth/1305031471.288603.png
1305031471.327642 rgb/1305031471.327642.png 1305031471.324440 depth/1305031471.324440.png
1305031471.359615 rgb/1305031471.359615.png 1305031471.356569 depth/1305031471.356569.png
1305031471.395730 rgb/1305031471.395730.png 1305031471.392751 depth/1305031471.392751.png
1305031471.427704 rgb/1305031471.427704.png 1305031471.424494 depth/1305031471.424494.png
1305031471.459647 rgb/1305031471.459647.png 1305031471.456975 depth/1305031471.456975.png
1305031471.496491 rgb/1305031471.496491.png 1305031471.492705 depth/1305031471.492705.png
1305031471.527624 rgb/1305031471.527624.png 1305031471.524343 depth/1305031471.524343.png
1305031471.559671 rgb/1305031471.559671.png 1305031471.556561 depth/1305031471.556561.png
1305031471.595702 rgb/1305031471.595702.png 1305031471.592606 depth/1305031471.592606.png
1305031471.627621 rgb/1305031471.627621.png 1305031471.624486 depth/1305031471.624486.png
1305031471.659642 rgb/1305031471.659642.png 1305031471.656831 depth/1305031471.656831.png
1305031471.695609 rgb/1305031471.695609.png 1305031471.693182 depth/1305031471.693182.png
1305031471.727501 rgb/1305031471.727501.png 1305031471.724753 depth/1305031471.724753.png
1305031471.759702 rgb/1305031471.759702.png 1305031471.753002 depth/1305031471.753002.png
1305031471.795801 rgb/1305031471.795801.png 1305031471.792706 depth/1305031471.792706.png
1305031471.827639 rgb/1305031471.827639.png 1305031471.823821 depth/1305031471.823821.png
1305031471.859665 rgb/1305031471.859665.png 1305031471.855793 depth/1305031471.855793.png
1305031471.895604 rgb/1305031471.895604.png 1305031471.892838 depth/1305031471.892838.png
1305031471.927651 rgb/1305031471.927651.png 1305031471.924928 depth/1305031471.924928.png
1305031471.959643 rgb/1305031471.959643.png 1305031471.957162 depth/1305031471.957162.png
1305031471.995573 rgb/1305031471.995573.png 1305031471.993177 depth/1305031471.993177.png
1305031472.027638 rgb/1305031472.027638.png 1305031472.024660 depth/1305031472.024660.png
1305031472.059668 rgb/1305031472.059668.png 1305031472.058063 depth/1305031472.058063.png
1305031472.095601 rgb/1305031472.095601.png 1305031472.092883 depth/1305031472.092883.png
1305031472.127594 rgb/1305031472.127594.png 1305031472.124760 depth/1305031472.124760.png
1305031472.159645 rgb/1305031472.159645.png 1305031472.156982 depth/1305031472.156982.png
1305031472.195682 rgb/1305031472.195682.png 1305031472.192890 depth/1305031472.192890.png
1305031472.227626 rgb/1305031472.227626.png 1305031472.224678 depth/1305031472.224678.png
1305031472.263840 rgb/1305031472.263840.png 1305031472.256642 depth/1305031472.256642.png
1305031472.295671 rgb/1305031472.295671.png 1305031472.293139 depth/1305031472.293139.png
1305031472.327678 rgb/1305031472.327678.png 1305031472.324844 depth/1305031472.324844.png
1305031472.363577 rgb/1305031472.363577.png 1305031472.360912 depth/1305031472.360912.png
1305031472.395599 rgb/1305031472.395599.png 1305031472.392956 depth/1305031472.392956.png
1305031472.427686 rgb/1305031472.427686.png 1305031472.424694 depth/1305031472.424694.png
1305031472.463603 rgb/1305031472.463603.png 1305031472.460919 depth/1305031472.460919.png
1305031472.495626 rgb/1305031472.495626.png 1305031472.492972 depth/1305031472.492972.png
1305031472.527625 rgb/1305031472.527625.png 1305031472.524781 depth/1305031472.524781.png
1305031472.563587 rgb/1305031472.563587.png 1305031472.561296 depth/1305031472.561296.png
1305031472.595675 rgb/1305031472.595675.png 1305031472.592968 depth/1305031472.592968.png
1305031472.627701 rgb/1305031472.627701.png 1305031472.624647 depth/1305031472.624647.png
1305031472.663575 rgb/1305031472.663575.png 1305031472.660836 depth/1305031472.660836.png
1305031472.695755 rgb/1305031472.695755.png 1305031472.693008 depth/1305031472.693008.png
1305031472.727628 rgb/1305031472.727628.png 1305031472.724752 depth/1305031472.724752.png
1305031472.763578 rgb/1305031472.763578.png 1305031472.760654 depth/1305031472.760654.png
1305031472.795640 rgb/1305031472.795640.png 1305031472.792775 depth/1305031472.792775.png
1305031472.827627 rgb/1305031472.827627.png 1305031472.824692 depth/1305031472.824692.png
1305031472.863598 rgb/1305031472.863598.png 1305031472.860936 depth/1305031472.860936.png
1305031472.895713 rgb/1305031472.895713.png 1305031472.892944 depth/1305031472.892944.png
1305031472.927685 rgb/1305031472.927685.png 1305031472.924814 depth/1305031472.924814.png
1305031472.963756 rgb/1305031472.963756.png 1305031472.961213 depth/1305031472.961213.png
1305031472.995704 rgb/1305031472.995704.png 1305031472.992815 depth/1305031472.992815.png
1305031473.027638 rgb/1305031473.027638.png 1305031473.024564 depth/1305031473.024564.png
1305031473.063684 rgb/1305031473.063684.png 1305031473.060795 depth/1305031473.060795.png
1305031473.095695 rgb/1305031473.095695.png 1305031473.092012 depth/1305031473.092012.png
1305031473.127744 rgb/1305031473.127744.png 1305031473.124072 depth/1305031473.124072.png
1305031473.167060 rgb/1305031473.167060.png 1305031473.158420 depth/1305031473.158420.png
1305031473.196069 rgb/1305031473.196069.png 1305031473.190828 depth/1305031473.190828.png
================================================
FILE: Examples/RGB-D/associations/fr1_desk2.txt
================================================
1305031526.671473 rgb/1305031526.671473.png 1305031526.688356 depth/1305031526.688356.png
1305031526.707547 rgb/1305031526.707547.png 1305031526.721587 depth/1305031526.721587.png
1305031526.771481 rgb/1305031526.771481.png 1305031526.755957 depth/1305031526.755957.png
1305031526.807455 rgb/1305031526.807455.png 1305031526.822643 depth/1305031526.822643.png
1305031526.871446 rgb/1305031526.871446.png 1305031526.856844 depth/1305031526.856844.png
1305031526.907484 rgb/1305031526.907484.png 1305031526.920578 depth/1305031526.920578.png
1305031526.939618 rgb/1305031526.939618.png 1305031526.955033 depth/1305031526.955033.png
1305031526.971510 rgb/1305031526.971510.png 1305031526.987606 depth/1305031526.987606.png
1305031527.007595 rgb/1305031527.007595.png 1305031527.020791 depth/1305031527.020791.png
1305031527.039512 rgb/1305031527.039512.png 1305031527.055070 depth/1305031527.055070.png
1305031527.071487 rgb/1305031527.071487.png 1305031527.086965 depth/1305031527.086965.png
1305031527.107498 rgb/1305031527.107498.png 1305031527.119854 depth/1305031527.119854.png
1305031527.139473 rgb/1305031527.139473.png 1305031527.155465 depth/1305031527.155465.png
1305031527.171540 rgb/1305031527.171540.png 1305031527.186447 depth/1305031527.186447.png
1305031527.207588 rgb/1305031527.207588.png 1305031527.222219 depth/1305031527.222219.png
1305031527.271501 rgb/1305031527.271501.png 1305031527.256275 depth/1305031527.256275.png
1305031527.307472 rgb/1305031527.307472.png 1305031527.323213 depth/1305031527.323213.png
1305031527.339636 rgb/1305031527.339636.png 1305031527.355197 depth/1305031527.355197.png
1305031527.371505 rgb/1305031527.371505.png 1305031527.388471 depth/1305031527.388471.png
1305031527.407412 rgb/1305031527.407412.png 1305031527.422926 depth/1305031527.422926.png
1305031527.439476 rgb/1305031527.439476.png 1305031527.455773 depth/1305031527.455773.png
1305031527.471497 rgb/1305031527.471497.png 1305031527.486055 depth/1305031527.486055.png
1305031527.507487 rgb/1305031527.507487.png 1305031527.522397 depth/1305031527.522397.png
1305031527.539741 rgb/1305031527.539741.png 1305031527.554573 depth/1305031527.554573.png
1305031527.571506 rgb/1305031527.571506.png 1305031527.586987 depth/1305031527.586987.png
1305031527.607559 rgb/1305031527.607559.png 1305031527.622793 depth/1305031527.622793.png
1305031527.671547 rgb/1305031527.671547.png 1305031527.656028 depth/1305031527.656028.png
1305031527.707520 rgb/1305031527.707520.png 1305031527.721751 depth/1305031527.721751.png
1305031527.771461 rgb/1305031527.771461.png 1305031527.756472 depth/1305031527.756472.png
1305031527.807581 rgb/1305031527.807581.png 1305031527.789333 depth/1305031527.789333.png
1305031527.839601 rgb/1305031527.839601.png 1305031527.825562 depth/1305031527.825562.png
1305031527.871464 rgb/1305031527.871464.png 1305031527.857855 depth/1305031527.857855.png
1305031527.907477 rgb/1305031527.907477.png 1305031527.922214 depth/1305031527.922214.png
1305031527.939566 rgb/1305031527.939566.png 1305031527.954490 depth/1305031527.954490.png
1305031527.971502 rgb/1305031527.971502.png 1305031527.987977 depth/1305031527.987977.png
1305031528.039560 rgb/1305031528.039560.png 1305031528.025614 depth/1305031528.025614.png
1305031528.071546 rgb/1305031528.071546.png 1305031528.085297 depth/1305031528.085297.png
1305031528.107513 rgb/1305031528.107513.png 1305031528.124333 depth/1305031528.124333.png
1305031528.139513 rgb/1305031528.139513.png 1305031528.151873 depth/1305031528.151873.png
1305031528.171523 rgb/1305031528.171523.png 1305031528.186872 depth/1305031528.186872.png
1305031528.207527 rgb/1305031528.207527.png 1305031528.220887 depth/1305031528.220887.png
1305031528.239493 rgb/1305031528.239493.png 1305031528.251953 depth/1305031528.251953.png
1305031528.275450 rgb/1305031528.275450.png 1305031528.284263 depth/1305031528.284263.png
1305031528.307665 rgb/1305031528.307665.png 1305031528.321639 depth/1305031528.321639.png
1305031528.339593 rgb/1305031528.339593.png 1305031528.355032 depth/1305031528.355032.png
1305031528.375435 rgb/1305031528.375435.png 1305031528.384839 depth/1305031528.384839.png
1305031528.407459 rgb/1305031528.407459.png 1305031528.424006 depth/1305031528.424006.png
1305031528.439469 rgb/1305031528.439469.png 1305031528.453962 depth/1305031528.453962.png
1305031528.475342 rgb/1305031528.475342.png 1305031528.490720 depth/1305031528.490720.png
1305031528.539626 rgb/1305031528.539626.png 1305031528.524649 depth/1305031528.524649.png
1305031528.575449 rgb/1305031528.575449.png 1305031528.557069 depth/1305031528.557069.png
1305031528.607841 rgb/1305031528.607841.png 1305031528.592924 depth/1305031528.592924.png
1305031528.639487 rgb/1305031528.639487.png 1305031528.654033 depth/1305031528.654033.png
1305031528.707447 rgb/1305031528.707447.png 1305031528.692143 depth/1305031528.692143.png
1305031528.739609 rgb/1305031528.739609.png 1305031528.725000 depth/1305031528.725000.png
1305031528.775443 rgb/1305031528.775443.png 1305031528.756620 depth/1305031528.756620.png
1305031528.807559 rgb/1305031528.807559.png 1305031528.792160 depth/1305031528.792160.png
1305031528.839572 rgb/1305031528.839572.png 1305031528.824057 depth/1305031528.824057.png
1305031528.875433 rgb/1305031528.875433.png 1305031528.856114 depth/1305031528.856114.png
1305031528.907519 rgb/1305031528.907519.png 1305031528.892684 depth/1305031528.892684.png
1305031528.939602 rgb/1305031528.939602.png 1305031528.924061 depth/1305031528.924061.png
1305031528.975465 rgb/1305031528.975465.png 1305031528.956027 depth/1305031528.956027.png
1305031529.007487 rgb/1305031529.007487.png 1305031528.991870 depth/1305031528.991870.png
1305031529.039494 rgb/1305031529.039494.png 1305031529.024164 depth/1305031529.024164.png
1305031529.075422 rgb/1305031529.075422.png 1305031529.057246 depth/1305031529.057246.png
1305031529.107523 rgb/1305031529.107523.png 1305031529.092696 depth/1305031529.092696.png
1305031529.139597 rgb/1305031529.139597.png 1305031529.124051 depth/1305031529.124051.png
1305031529.175411 rgb/1305031529.175411.png 1305031529.156187 depth/1305031529.156187.png
1305031529.207466 rgb/1305031529.207466.png 1305031529.192085 depth/1305031529.192085.png
1305031529.239515 rgb/1305031529.239515.png 1305031529.224200 depth/1305031529.224200.png
1305031529.275389 rgb/1305031529.275389.png 1305031529.291235 depth/1305031529.291235.png
1305031529.307413 rgb/1305031529.307413.png 1305031529.323356 depth/1305031529.323356.png
1305031529.339486 rgb/1305031529.339486.png 1305031529.355813 depth/1305031529.355813.png
1305031529.375399 rgb/1305031529.375399.png 1305031529.388855 depth/1305031529.388855.png
1305031529.407513 rgb/1305031529.407513.png 1305031529.423010 depth/1305031529.423010.png
1305031529.439502 rgb/1305031529.439502.png 1305031529.457448 depth/1305031529.457448.png
1305031529.475403 rgb/1305031529.475403.png 1305031529.491343 depth/1305031529.491343.png
1305031529.507485 rgb/1305031529.507485.png 1305031529.522171 depth/1305031529.522171.png
1305031529.539489 rgb/1305031529.539489.png 1305031529.556350 depth/1305031529.556350.png
1305031529.607479 rgb/1305031529.607479.png 1305031529.593324 depth/1305031529.593324.png
1305031529.639746 rgb/1305031529.639746.png 1305031529.623772 depth/1305031529.623772.png
1305031529.675618 rgb/1305031529.675618.png 1305031529.657753 depth/1305031529.657753.png
1305031529.707557 rgb/1305031529.707557.png 1305031529.692840 depth/1305031529.692840.png
1305031529.739568 rgb/1305031529.739568.png 1305031529.725566 depth/1305031529.725566.png
1305031529.775501 rgb/1305031529.775501.png 1305031529.759598 depth/1305031529.759598.png
1305031529.807516 rgb/1305031529.807516.png 1305031529.792805 depth/1305031529.792805.png
1305031529.839505 rgb/1305031529.839505.png 1305031529.825293 depth/1305031529.825293.png
1305031529.875495 rgb/1305031529.875495.png 1305031529.891119 depth/1305031529.891119.png
1305031529.939498 rgb/1305031529.939498.png 1305031529.925850 depth/1305031529.925850.png
1305031529.975501 rgb/1305031529.975501.png 1305031529.960102 depth/1305031529.960102.png
1305031530.007409 rgb/1305031530.007409.png 1305031529.992331 depth/1305031529.992331.png
1305031530.039454 rgb/1305031530.039454.png 1305031530.024225 depth/1305031530.024225.png
1305031530.075443 rgb/1305031530.075443.png 1305031530.059982 depth/1305031530.059982.png
1305031530.107445 rgb/1305031530.107445.png 1305031530.091203 depth/1305031530.091203.png
1305031530.139497 rgb/1305031530.139497.png 1305031530.125990 depth/1305031530.125990.png
1305031530.175410 rgb/1305031530.175410.png 1305031530.159636 depth/1305031530.159636.png
1305031530.207486 rgb/1305031530.207486.png 1305031530.191494 depth/1305031530.191494.png
1305031530.239446 rgb/1305031530.239446.png 1305031530.224007 depth/1305031530.224007.png
1305031530.275407 rgb/1305031530.275407.png 1305031530.259074 depth/1305031530.259074.png
1305031530.307544 rgb/1305031530.307544.png 1305031530.292738 depth/1305031530.292738.png
1305031530.339724 rgb/1305031530.339724.png 1305031530.324398 depth/1305031530.324398.png
1305031530.375386 rgb/1305031530.375386.png 1305031530.355958 depth/1305031530.355958.png
1305031530.407465 rgb/1305031530.407465.png 1305031530.391987 depth/1305031530.391987.png
1305031530.439553 rgb/1305031530.439553.png 1305031530.423101 depth/1305031530.423101.png
1305031530.475439 rgb/1305031530.475439.png 1305031530.458850 depth/1305031530.458850.png
1305031530.507461 rgb/1305031530.507461.png 1305031530.492200 depth/1305031530.492200.png
1305031530.539532 rgb/1305031530.539532.png 1305031530.524323 depth/1305031530.524323.png
1305031530.575433 rgb/1305031530.575433.png 1305031530.591301 depth/1305031530.591301.png
1305031530.607559 rgb/1305031530.607559.png 1305031530.623002 depth/1305031530.623002.png
1305031530.639507 rgb/1305031530.639507.png 1305031530.656445 depth/1305031530.656445.png
1305031530.675401 rgb/1305031530.675401.png 1305031530.691015 depth/1305031530.691015.png
1305031530.739522 rgb/1305031530.739522.png 1305031530.723869 depth/1305031530.723869.png
1305031530.775437 rgb/1305031530.775437.png 1305031530.790818 depth/1305031530.790818.png
1305031530.807467 rgb/1305031530.807467.png 1305031530.822584 depth/1305031530.822584.png
1305031530.839463 rgb/1305031530.839463.png 1305031530.858371 depth/1305031530.858371.png
1305031530.875401 rgb/1305031530.875401.png 1305031530.890688 depth/1305031530.890688.png
1305031530.939462 rgb/1305031530.939462.png 1305031530.923878 depth/1305031530.923878.png
1305031530.975286 rgb/1305031530.975286.png 1305031530.988081 depth/1305031530.988081.png
1305031531.039689 rgb/1305031531.039689.png 1305031531.027310 depth/1305031531.027310.png
1305031531.075325 rgb/1305031531.075325.png 1305031531.091208 depth/1305031531.091208.png
1305031531.139581 rgb/1305031531.139581.png 1305031531.126140 depth/1305031531.126140.png
1305031531.175355 rgb/1305031531.175355.png 1305031531.190137 depth/1305031531.190137.png
1305031531.239619 rgb/1305031531.239619.png 1305031531.228127 depth/1305031531.228127.png
1305031531.275515 rgb/1305031531.275515.png 1305031531.290185 depth/1305031531.290185.png
1305031531.339595 rgb/1305031531.339595.png 1305031531.327763 depth/1305031531.327763.png
1305031531.375434 rgb/1305031531.375434.png 1305031531.389868 depth/1305031531.389868.png
1305031531.439644 rgb/1305031531.439644.png 1305031531.427177 depth/1305031531.427177.png
1305031531.475324 rgb/1305031531.475324.png 1305031531.459698 depth/1305031531.459698.png
1305031531.507602 rgb/1305031531.507602.png 1305031531.492107 depth/1305031531.492107.png
1305031531.539487 rgb/1305031531.539487.png 1305031531.527542 depth/1305031531.527542.png
1305031531.575392 rgb/1305031531.575392.png 1305031531.560506 depth/1305031531.560506.png
1305031531.607419 rgb/1305031531.607419.png 1305031531.592018 depth/1305031531.592018.png
1305031531.639521 rgb/1305031531.639521.png 1305031531.628037 depth/1305031531.628037.png
1305031531.675444 rgb/1305031531.675444.png 1305031531.659769 depth/1305031531.659769.png
1305031531.707498 rgb/1305031531.707498.png 1305031531.693140 depth/1305031531.693140.png
1305031531.739657 rgb/1305031531.739657.png 1305031531.727762 depth/1305031531.727762.png
1305031531.775442 rgb/1305031531.775442.png 1305031531.790528 depth/1305031531.790528.png
1305031531.839545 rgb/1305031531.839545.png 1305031531.826931 depth/1305031531.826931.png
1305031531.875426 rgb/1305031531.875426.png 1305031531.858402 depth/1305031531.858402.png
1305031531.907427 rgb/1305031531.907427.png 1305031531.893291 depth/1305031531.893291.png
1305031531.939564 rgb/1305031531.939564.png 1305031531.925080 depth/1305031531.925080.png
1305031531.975488 rgb/1305031531.975488.png 1305031531.990634 depth/1305031531.990634.png
1305031532.039675 rgb/1305031532.039675.png 1305031532.027524 depth/1305031532.027524.png
1305031532.075525 rgb/1305031532.075525.png 1305031532.059872 depth/1305031532.059872.png
1305031532.107398 rgb/1305031532.107398.png 1305031532.092096 depth/1305031532.092096.png
1305031532.139520 rgb/1305031532.139520.png 1305031532.126073 depth/1305031532.126073.png
1305031532.175563 rgb/1305031532.175563.png 1305031532.159926 depth/1305031532.159926.png
1305031532.207465 rgb/1305031532.207465.png 1305031532.195623 depth/1305031532.195623.png
1305031532.239966 rgb/1305031532.239966.png 1305031532.227800 depth/1305031532.227800.png
1305031532.275514 rgb/1305031532.275514.png 1305031532.260079 depth/1305031532.260079.png
1305031532.307481 rgb/1305031532.307481.png 1305031532.295824 depth/1305031532.295824.png
1305031532.339777 rgb/1305031532.339777.png 1305031532.327833 depth/1305031532.327833.png
1305031532.375496 rgb/1305031532.375496.png 1305031532.356687 depth/1305031532.356687.png
1305031532.407448 rgb/1305031532.407448.png 1305031532.396584 depth/1305031532.396584.png
1305031532.439533 rgb/1305031532.439533.png 1305031532.424572 depth/1305031532.424572.png
1305031532.475428 rgb/1305031532.475428.png 1305031532.461447 depth/1305031532.461447.png
1305031532.507415 rgb/1305031532.507415.png 1305031532.494758 depth/1305031532.494758.png
1305031532.539458 rgb/1305031532.539458.png 1305031532.523363 depth/1305031532.523363.png
1305031532.575435 rgb/1305031532.575435.png 1305031532.558750 depth/1305031532.558750.png
1305031532.607434 rgb/1305031532.607434.png 1305031532.594713 depth/1305031532.594713.png
1305031532.639592 rgb/1305031532.639592.png 1305031532.626577 depth/1305031532.626577.png
1305031532.707308 rgb/1305031532.707308.png 1305031532.692281 depth/1305031532.692281.png
1305031532.740052 rgb/1305031532.740052.png 1305031532.725142 depth/1305031532.725142.png
1305031532.775761 rgb/1305031532.775761.png 1305031532.756518 depth/1305031532.756518.png
1305031532.807429 rgb/1305031532.807429.png 1305031532.793593 depth/1305031532.793593.png
1305031532.839717 rgb/1305031532.839717.png 1305031532.827589 depth/1305031532.827589.png
1305031532.875476 rgb/1305031532.875476.png 1305031532.860360 depth/1305031532.860360.png
1305031532.907577 rgb/1305031532.907577.png 1305031532.894951 depth/1305031532.894951.png
1305031532.939523 rgb/1305031532.939523.png 1305031532.927108 depth/1305031532.927108.png
1305031532.975424 rgb/1305031532.975424.png 1305031532.958860 depth/1305031532.958860.png
1305031533.007402 rgb/1305031533.007402.png 1305031532.994889 depth/1305031532.994889.png
1305031533.039505 rgb/1305031533.039505.png 1305031533.027007 depth/1305031533.027007.png
1305031533.075500 rgb/1305031533.075500.png 1305031533.059895 depth/1305031533.059895.png
1305031533.107480 rgb/1305031533.107480.png 1305031533.095707 depth/1305031533.095707.png
1305031533.139514 rgb/1305031533.139514.png 1305031533.127261 depth/1305031533.127261.png
1305031533.175459 rgb/1305031533.175459.png 1305031533.158865 depth/1305031533.158865.png
1305031533.207507 rgb/1305031533.207507.png 1305031533.194665 depth/1305031533.194665.png
1305031533.239511 rgb/1305031533.239511.png 1305031533.226596 depth/1305031533.226596.png
1305031533.275405 rgb/1305031533.275405.png 1305031533.258719 depth/1305031533.258719.png
1305031533.307502 rgb/1305031533.307502.png 1305031533.294892 depth/1305031533.294892.png
1305031533.339522 rgb/1305031533.339522.png 1305031533.326747 depth/1305031533.326747.png
1305031533.375654 rgb/1305031533.375654.png 1305031533.358749 depth/1305031533.358749.png
1305031533.407483 rgb/1305031533.407483.png 1305031533.394869 depth/1305031533.394869.png
1305031533.439774 rgb/1305031533.439774.png 1305031533.428282 depth/1305031533.428282.png
1305031533.475654 rgb/1305031533.475654.png 1305031533.463804 depth/1305031533.463804.png
1305031533.507463 rgb/1305031533.507463.png 1305031533.495077 depth/1305031533.495077.png
1305031533.539640 rgb/1305031533.539640.png 1305031533.523787 depth/1305031533.523787.png
1305031533.575643 rgb/1305031533.575643.png 1305031533.563866 depth/1305031533.563866.png
1305031533.607639 rgb/1305031533.607639.png 1305031533.596729 depth/1305031533.596729.png
1305031533.639561 rgb/1305031533.639561.png 1305031533.623714 depth/1305031533.623714.png
1305031533.675446 rgb/1305031533.675446.png 1305031533.662973 depth/1305031533.662973.png
1305031533.707501 rgb/1305031533.707501.png 1305031533.695127 depth/1305031533.695127.png
1305031533.739555 rgb/1305031533.739555.png 1305031533.727956 depth/1305031533.727956.png
1305031533.775530 rgb/1305031533.775530.png 1305031533.763534 depth/1305031533.763534.png
1305031533.807707 rgb/1305031533.807707.png 1305031533.795519 depth/1305031533.795519.png
1305031533.839329 rgb/1305031533.839329.png 1305031533.827015 depth/1305031533.827015.png
1305031533.875471 rgb/1305031533.875471.png 1305031533.859819 depth/1305031533.859819.png
1305031533.907441 rgb/1305031533.907441.png 1305031533.895161 depth/1305031533.895161.png
1305031533.939530 rgb/1305031533.939530.png 1305031533.926857 depth/1305031533.926857.png
1305031533.975439 rgb/1305031533.975439.png 1305031533.961985 depth/1305031533.961985.png
1305031534.007323 rgb/1305031534.007323.png 1305031533.994392 depth/1305031533.994392.png
1305031534.039458 rgb/1305031534.039458.png 1305031534.026608 depth/1305031534.026608.png
1305031534.075484 rgb/1305031534.075484.png 1305031534.062247 depth/1305031534.062247.png
1305031534.107442 rgb/1305031534.107442.png 1305031534.094417 depth/1305031534.094417.png
1305031534.139529 rgb/1305031534.139529.png 1305031534.126412 depth/1305031534.126412.png
1305031534.175381 rgb/1305031534.175381.png 1305031534.162210 depth/1305031534.162210.png
1305031534.207436 rgb/1305031534.207436.png 1305031534.191161 depth/1305031534.191161.png
1305031534.239529 rgb/1305031534.239529.png 1305031534.225977 depth/1305031534.225977.png
1305031534.275475 rgb/1305031534.275475.png 1305031534.262752 depth/1305031534.262752.png
1305031534.307945 rgb/1305031534.307945.png 1305031534.295276 depth/1305031534.295276.png
1305031534.339859 rgb/1305031534.339859.png 1305031534.327593 depth/1305031534.327593.png
1305031534.375478 rgb/1305031534.375478.png 1305031534.362839 depth/1305031534.362839.png
1305031534.407595 rgb/1305031534.407595.png 1305031534.395128 depth/1305031534.395128.png
1305031534.439543 rgb/1305031534.439543.png 1305031534.427890 depth/1305031534.427890.png
1305031534.475605 rgb/1305031534.475605.png 1305031534.462407 depth/1305031534.462407.png
1305031534.507525 rgb/1305031534.507525.png 1305031534.494488 depth/1305031534.494488.png
1305031534.539582 rgb/1305031534.539582.png 1305031534.526222 depth/1305031534.526222.png
1305031534.575414 rgb/1305031534.575414.png 1305031534.562364 depth/1305031534.562364.png
1305031534.607494 rgb/1305031534.607494.png 1305031534.594279 depth/1305031534.594279.png
1305031534.639696 rgb/1305031534.639696.png 1305031534.627133 depth/1305031534.627133.png
1305031534.675511 rgb/1305031534.675511.png 1305031534.662781 depth/1305031534.662781.png
1305031534.707481 rgb/1305031534.707481.png 1305031534.694710 depth/1305031534.694710.png
1305031534.739665 rgb/1305031534.739665.png 1305031534.730855 depth/1305031534.730855.png
1305031534.775491 rgb/1305031534.775491.png 1305031534.763129 depth/1305031534.763129.png
1305031534.807516 rgb/1305031534.807516.png 1305031534.795824 depth/1305031534.795824.png
1305031534.839569 rgb/1305031534.839569.png 1305031534.831135 depth/1305031534.831135.png
1305031534.875499 rgb/1305031534.875499.png 1305031534.862751 depth/1305031534.862751.png
1305031534.907458 rgb/1305031534.907458.png 1305031534.894919 depth/1305031534.894919.png
1305031534.939556 rgb/1305031534.939556.png 1305031534.930974 depth/1305031534.930974.png
1305031534.975464 rgb/1305031534.975464.png 1305031534.962776 depth/1305031534.962776.png
1305031535.007643 rgb/1305031535.007643.png 1305031534.994599 depth/1305031534.994599.png
1305031535.039655 rgb/1305031535.039655.png 1305031535.030642 depth/1305031535.030642.png
1305031535.075490 rgb/1305031535.075490.png 1305031535.062210 depth/1305031535.062210.png
1305031535.107796 rgb/1305031535.107796.png 1305031535.094542 depth/1305031535.094542.png
1305031535.139465 rgb/1305031535.139465.png 1305031535.129807 depth/1305031535.129807.png
1305031535.175406 rgb/1305031535.175406.png 1305031535.158853 depth/1305031535.158853.png
1305031535.207514 rgb/1305031535.207514.png 1305031535.193991 depth/1305031535.193991.png
1305031535.239511 rgb/1305031535.239511.png 1305031535.230011 depth/1305031535.230011.png
1305031535.275537 rgb/1305031535.275537.png 1305031535.261725 depth/1305031535.261725.png
1305031535.307409 rgb/1305031535.307409.png 1305031535.295784 depth/1305031535.295784.png
1305031535.339468 rgb/1305031535.339468.png 1305031535.329773 depth/1305031535.329773.png
1305031535.375492 rgb/1305031535.375492.png 1305031535.361759 depth/1305031535.361759.png
1305031535.407712 rgb/1305031535.407712.png 1305031535.392026 depth/1305031535.392026.png
1305031535.439618 rgb/1305031535.439618.png 1305031535.431010 depth/1305031535.431010.png
1305031535.475595 rgb/1305031535.475595.png 1305031535.462732 depth/1305031535.462732.png
1305031535.507701 rgb/1305031535.507701.png 1305031535.495467 depth/1305031535.495467.png
1305031535.539515 rgb/1305031535.539515.png 1305031535.530835 depth/1305031535.530835.png
1305031535.575567 rgb/1305031535.575567.png 1305031535.562308 depth/1305031535.562308.png
1305031535.607524 rgb/1305031535.607524.png 1305031535.594713 depth/1305031535.594713.png
1305031535.639591 rgb/1305031535.639591.png 1305031535.630819 depth/1305031535.630819.png
1305031535.675500 rgb/1305031535.675500.png 1305031535.662546 depth/1305031535.662546.png
1305031535.707524 rgb/1305031535.707524.png 1305031535.694763 depth/1305031535.694763.png
1305031535.739708 rgb/1305031535.739708.png 1305031535.730877 depth/1305031535.730877.png
1305031535.775437 rgb/1305031535.775437.png 1305031535.759227 depth/1305031535.759227.png
1305031535.807496 rgb/1305031535.807496.png 1305031535.794599 depth/1305031535.794599.png
1305031535.840053 rgb/1305031535.840053.png 1305031535.831105 depth/1305031535.831105.png
1305031535.875502 rgb/1305031535.875502.png 1305031535.859528 depth/1305031535.859528.png
1305031535.907487 rgb/1305031535.907487.png 1305031535.898883 depth/1305031535.898883.png
1305031535.939747 rgb/1305031535.939747.png 1305031535.930685 depth/1305031535.930685.png
1305031535.975512 rgb/1305031535.975512.png 1305031535.959567 depth/1305031535.959567.png
1305031536.007462 rgb/1305031536.007462.png 1305031535.998988 depth/1305031535.998988.png
1305031536.039667 rgb/1305031536.039667.png 1305031536.031463 depth/1305031536.031463.png
1305031536.075538 rgb/1305031536.075538.png 1305031536.062243 depth/1305031536.062243.png
1305031536.107579 rgb/1305031536.107579.png 1305031536.099404 depth/1305031536.099404.png
1305031536.139540 rgb/1305031536.139540.png 1305031536.131440 depth/1305031536.131440.png
1305031536.175699 rgb/1305031536.175699.png 1305031536.163367 depth/1305031536.163367.png
1305031536.207474 rgb/1305031536.207474.png 1305031536.199777 depth/1305031536.199777.png
1305031536.239482 rgb/1305031536.239482.png 1305031536.231583 depth/1305031536.231583.png
1305031536.275618 rgb/1305031536.275618.png 1305031536.263219 depth/1305031536.263219.png
1305031536.307472 rgb/1305031536.307472.png 1305031536.299512 depth/1305031536.299512.png
1305031536.339530 rgb/1305031536.339530.png 1305031536.331390 depth/1305031536.331390.png
1305031536.375786 rgb/1305031536.375786.png 1305031536.363006 depth/1305031536.363006.png
1305031536.407665 rgb/1305031536.407665.png 1305031536.399605 depth/1305031536.399605.png
1305031536.439546 rgb/1305031536.439546.png 1305031536.431590 depth/1305031536.431590.png
1305031536.475492 rgb/1305031536.475492.png 1305031536.463554 depth/1305031536.463554.png
1305031536.507648 rgb/1305031536.507648.png 1305031536.499647 depth/1305031536.499647.png
1305031536.539583 rgb/1305031536.539583.png 1305031536.531617 depth/1305031536.531617.png
1305031536.575660 rgb/1305031536.575660.png 1305031536.563087 depth/1305031536.563087.png
1305031536.607624 rgb/1305031536.607624.png 1305031536.599164 depth/1305031536.599164.png
1305031536.639838 rgb/1305031536.639838.png 1305031536.631797 depth/1305031536.631797.png
1305031536.675456 rgb/1305031536.675456.png 1305031536.663533 depth/1305031536.663533.png
1305031536.707472 rgb/1305031536.707472.png 1305031536.699497 depth/1305031536.699497.png
1305031536.739722 rgb/1305031536.739722.png 1305031536.731424 depth/1305031536.731424.png
1305031536.775321 rgb/1305031536.775321.png 1305031536.761478 depth/1305031536.761478.png
1305031536.807301 rgb/1305031536.807301.png 1305031536.796242 depth/1305031536.796242.png
1305031536.839527 rgb/1305031536.839527.png 1305031536.828016 depth/1305031536.828016.png
1305031536.875419 rgb/1305031536.875419.png 1305031536.859596 depth/1305031536.859596.png
1305031536.907491 rgb/1305031536.907491.png 1305031536.895830 depth/1305031536.895830.png
1305031536.939530 rgb/1305031536.939530.png 1305031536.927579 depth/1305031536.927579.png
1305031536.975375 rgb/1305031536.975375.png 1305031536.962880 depth/1305031536.962880.png
1305031537.007412 rgb/1305031537.007412.png 1305031536.996766 depth/1305031536.996766.png
1305031537.039427 rgb/1305031537.039427.png 1305031537.028058 depth/1305031537.028058.png
1305031537.075341 rgb/1305031537.075341.png 1305031537.060447 depth/1305031537.060447.png
1305031537.107337 rgb/1305031537.107337.png 1305031537.095829 depth/1305031537.095829.png
1305031537.140656 rgb/1305031537.140656.png 1305031537.129621 depth/1305031537.129621.png
1305031537.175377 rgb/1305031537.175377.png 1305031537.167541 depth/1305031537.167541.png
1305031537.207445 rgb/1305031537.207445.png 1305031537.195643 depth/1305031537.195643.png
1305031537.239415 rgb/1305031537.239415.png 1305031537.230153 depth/1305031537.230153.png
1305031537.275504 rgb/1305031537.275504.png 1305031537.265688 depth/1305031537.265688.png
1305031537.307646 rgb/1305031537.307646.png 1305031537.298861 depth/1305031537.298861.png
1305031537.339718 rgb/1305031537.339718.png 1305031537.330994 depth/1305031537.330994.png
1305031537.375388 rgb/1305031537.375388.png 1305031537.365736 depth/1305031537.365736.png
1305031537.407396 rgb/1305031537.407396.png 1305031537.395624 depth/1305031537.395624.png
1305031537.439649 rgb/1305031537.439649.png 1305031537.429641 depth/1305031537.429641.png
1305031537.475520 rgb/1305031537.475520.png 1305031537.464312 depth/1305031537.464312.png
1305031537.507492 rgb/1305031537.507492.png 1305031537.497527 depth/1305031537.497527.png
1305031537.539497 rgb/1305031537.539497.png 1305031537.530263 depth/1305031537.530263.png
1305031537.575529 rgb/1305031537.575529.png 1305031537.564476 depth/1305031537.564476.png
1305031537.607507 rgb/1305031537.607507.png 1305031537.598276 depth/1305031537.598276.png
1305031537.643442 rgb/1305031537.643442.png 1305031537.630389 depth/1305031537.630389.png
1305031537.675306 rgb/1305031537.675306.png 1305031537.664114 depth/1305031537.664114.png
1305031537.707483 rgb/1305031537.707483.png 1305031537.695278 depth/1305031537.695278.png
1305031537.743426 rgb/1305031537.743426.png 1305031537.728342 depth/1305031537.728342.png
1305031537.775469 rgb/1305031537.775469.png 1305031537.766378 depth/1305031537.766378.png
1305031537.807576 rgb/1305031537.807576.png 1305031537.798725 depth/1305031537.798725.png
1305031537.843458 rgb/1305031537.843458.png 1305031537.830287 depth/1305031537.830287.png
1305031537.875571 rgb/1305031537.875571.png 1305031537.866662 depth/1305031537.866662.png
1305031537.907514 rgb/1305031537.907514.png 1305031537.898536 depth/1305031537.898536.png
1305031537.943469 rgb/1305031537.943469.png 1305031537.930243 depth/1305031537.930243.png
1305031537.975426 rgb/1305031537.975426.png 1305031537.966300 depth/1305031537.966300.png
1305031538.007529 rgb/1305031538.007529.png 1305031537.998327 depth/1305031537.998327.png
1305031538.043452 rgb/1305031538.043452.png 1305031538.030606 depth/1305031538.030606.png
1305031538.075565 rgb/1305031538.075565.png 1305031538.066420 depth/1305031538.066420.png
1305031538.107629 rgb/1305031538.107629.png 1305031538.099117 depth/1305031538.099117.png
1305031538.143487 rgb/1305031538.143487.png 1305031538.130778 depth/1305031538.130778.png
1305031538.175565 rgb/1305031538.175565.png 1305031538.167361 depth/1305031538.167361.png
1305031538.207697 rgb/1305031538.207697.png 1305031538.198836 depth/1305031538.198836.png
1305031538.243517 rgb/1305031538.243517.png 1305031538.231674 depth/1305031538.231674.png
1305031538.275489 rgb/1305031538.275489.png 1305031538.267245 depth/1305031538.267245.png
1305031538.307386 rgb/1305031538.307386.png 1305031538.297169 depth/1305031538.297169.png
1305031538.343413 rgb/1305031538.343413.png 1305031538.329631 depth/1305031538.329631.png
1305031538.375553 rgb/1305031538.375553.png 1305031538.366671 depth/1305031538.366671.png
1305031538.407511 rgb/1305031538.407511.png 1305031538.395653 depth/1305031538.395653.png
1305031538.443598 rgb/1305031538.443598.png 1305031538.434273 depth/1305031538.434273.png
1305031538.475570 rgb/1305031538.475570.png 1305031538.468114 depth/1305031538.468114.png
1305031538.507548 rgb/1305031538.507548.png 1305031538.498490 depth/1305031538.498490.png
1305031538.543450 rgb/1305031538.543450.png 1305031538.534659 depth/1305031538.534659.png
1305031538.575524 rgb/1305031538.575524.png 1305031538.566473 depth/1305031538.566473.png
1305031538.607517 rgb/1305031538.607517.png 1305031538.598497 depth/1305031538.598497.png
1305031538.643479 rgb/1305031538.643479.png 1305031538.634075 depth/1305031538.634075.png
1305031538.675433 rgb/1305031538.675433.png 1305031538.666052 depth/1305031538.666052.png
1305031538.707490 rgb/1305031538.707490.png 1305031538.698387 depth/1305031538.698387.png
1305031538.743572 rgb/1305031538.743572.png 1305031538.734584 depth/1305031538.734584.png
1305031538.775491 rgb/1305031538.775491.png 1305031538.766510 depth/1305031538.766510.png
1305031538.808089 rgb/1305031538.808089.png 1305031538.798755 depth/1305031538.798755.png
1305031538.843518 rgb/1305031538.843518.png 1305031538.832497 depth/1305031538.832497.png
1305031538.875656 rgb/1305031538.875656.png 1305031538.867193 depth/1305031538.867193.png
1305031538.907498 rgb/1305031538.907498.png 1305031538.899432 depth/1305031538.899432.png
1305031538.943414 rgb/1305031538.943414.png 1305031538.936017 depth/1305031538.936017.png
1305031538.975507 rgb/1305031538.975507.png 1305031538.967667 depth/1305031538.967667.png
1305031539.007520 rgb/1305031539.007520.png 1305031538.999448 depth/1305031538.999448.png
1305031539.043445 rgb/1305031539.043445.png 1305031539.034977 depth/1305031539.034977.png
1305031539.075515 rgb/1305031539.075515.png 1305031539.067603 depth/1305031539.067603.png
1305031539.107503 rgb/1305031539.107503.png 1305031539.099360 depth/1305031539.099360.png
1305031539.143607 rgb/1305031539.143607.png 1305031539.135768 depth/1305031539.135768.png
1305031539.175587 rgb/1305031539.175587.png 1305031539.167546 depth/1305031539.167546.png
1305031539.207601 rgb/1305031539.207601.png 1305031539.199492 depth/1305031539.199492.png
1305031539.243449 rgb/1305031539.243449.png 1305031539.235629 depth/1305031539.235629.png
1305031539.275652 rgb/1305031539.275652.png 1305031539.267760 depth/1305031539.267760.png
1305031539.307521 rgb/1305031539.307521.png 1305031539.299592 depth/1305031539.299592.png
1305031539.343842 rgb/1305031539.343842.png 1305031539.335706 depth/1305031539.335706.png
1305031539.375556 rgb/1305031539.375556.png 1305031539.367585 depth/1305031539.367585.png
1305031539.407846 rgb/1305031539.407846.png 1305031539.399501 depth/1305031539.399501.png
1305031539.443431 rgb/1305031539.443431.png 1305031539.435549 depth/1305031539.435549.png
1305031539.475605 rgb/1305031539.475605.png 1305031539.467525 depth/1305031539.467525.png
1305031539.507506 rgb/1305031539.507506.png 1305031539.499639 depth/1305031539.499639.png
1305031539.543459 rgb/1305031539.543459.png 1305031539.535499 depth/1305031539.535499.png
1305031539.575448 rgb/1305031539.575448.png 1305031539.567517 depth/1305031539.567517.png
1305031539.607559 rgb/1305031539.607559.png 1305031539.599060 depth/1305031539.599060.png
1305031539.643437 rgb/1305031539.643437.png 1305031539.635592 depth/1305031539.635592.png
1305031539.675458 rgb/1305031539.675458.png 1305031539.667412 depth/1305031539.667412.png
1305031539.707426 rgb/1305031539.707426.png 1305031539.703794 depth/1305031539.703794.png
1305031539.743465 rgb/1305031539.743465.png 1305031539.735675 depth/1305031539.735675.png
1305031539.775488 rgb/1305031539.775488.png 1305031539.767637 depth/1305031539.767637.png
1305031539.807653 rgb/1305031539.807653.png 1305031539.803605 depth/1305031539.803605.png
1305031539.843466 rgb/1305031539.843466.png 1305031539.832088 depth/1305031539.832088.png
1305031539.875593 rgb/1305031539.875593.png 1305031539.867127 depth/1305031539.867127.png
1305031539.907642 rgb/1305031539.907642.png 1305031539.903594 depth/1305031539.903594.png
1305031539.943541 rgb/1305031539.943541.png 1305031539.935437 depth/1305031539.935437.png
1305031539.975883 rgb/1305031539.975883.png 1305031539.967652 depth/1305031539.967652.png
1305031540.007422 rgb/1305031540.007422.png 1305031540.003691 depth/1305031540.003691.png
1305031540.043468 rgb/1305031540.043468.png 1305031540.035614 depth/1305031540.035614.png
1305031540.075632 rgb/1305031540.075632.png 1305031540.067782 depth/1305031540.067782.png
1305031540.107421 rgb/1305031540.107421.png 1305031540.103651 depth/1305031540.103651.png
1305031540.143443 rgb/1305031540.143443.png 1305031540.135787 depth/1305031540.135787.png
1305031540.175595 rgb/1305031540.175595.png 1305031540.167625 depth/1305031540.167625.png
1305031540.207411 rgb/1305031540.207411.png 1305031540.204012 depth/1305031540.204012.png
1305031540.243496 rgb/1305031540.243496.png 1305031540.235943 depth/1305031540.235943.png
1305031540.275604 rgb/1305031540.275604.png 1305031540.267794 depth/1305031540.267794.png
1305031540.307411 rgb/1305031540.307411.png 1305031540.303627 depth/1305031540.303627.png
1305031540.343456 rgb/1305031540.343456.png 1305031540.335660 depth/1305031540.335660.png
1305031540.375438 rgb/1305031540.375438.png 1305031540.367613 depth/1305031540.367613.png
1305031540.407504 rgb/1305031540.407504.png 1305031540.403545 depth/1305031540.403545.png
1305031540.443453 rgb/1305031540.443453.png 1305031540.435756 depth/1305031540.435756.png
1305031540.475476 rgb/1305031540.475476.png 1305031540.467365 depth/1305031540.467365.png
1305031540.507525 rgb/1305031540.507525.png 1305031540.502953 depth/1305031540.502953.png
1305031540.543427 rgb/1305031540.543427.png 1305031540.535194 depth/1305031540.535194.png
1305031540.575635 rgb/1305031540.575635.png 1305031540.563522 depth/1305031540.563522.png
1305031540.607508 rgb/1305031540.607508.png 1305031540.603376 depth/1305031540.603376.png
1305031540.643443 rgb/1305031540.643443.png 1305031540.635224 depth/1305031540.635224.png
1305031540.675895 rgb/1305031540.675895.png 1305031540.667294 depth/1305031540.667294.png
1305031540.707442 rgb/1305031540.707442.png 1305031540.703386 depth/1305031540.703386.png
1305031540.743545 rgb/1305031540.743545.png 1305031540.735694 depth/1305031540.735694.png
1305031540.775513 rgb/1305031540.775513.png 1305031540.767548 depth/1305031540.767548.png
1305031540.807495 rgb/1305031540.807495.png 1305031540.803232 depth/1305031540.803232.png
1305031540.843557 rgb/1305031540.843557.png 1305031540.835181 depth/1305031540.835181.png
1305031540.875472 rgb/1305031540.875472.png 1305031540.871023 depth/1305031540.871023.png
1305031540.907447 rgb/1305031540.907447.png 1305031540.903222 depth/1305031540.903222.png
1305031540.943442 rgb/1305031540.943442.png 1305031540.935050 depth/1305031540.935050.png
1305031540.975401 rgb/1305031540.975401.png 1305031540.971078 depth/1305031540.971078.png
1305031541.007473 rgb/1305031541.007473.png 1305031541.003228 depth/1305031541.003228.png
1305031541.043464 rgb/1305031541.043464.png 1305031541.034514 depth/1305031541.034514.png
1305031541.075485 rgb/1305031541.075485.png 1305031541.070217 depth/1305031541.070217.png
1305031541.107513 rgb/1305031541.107513.png 1305031541.099997 depth/1305031541.099997.png
1305031541.143507 rgb/1305031541.143507.png 1305031541.135330 depth/1305031541.135330.png
1305031541.175472 rgb/1305031541.175472.png 1305031541.171574 depth/1305031541.171574.png
1305031541.207454 rgb/1305031541.207454.png 1305031541.202996 depth/1305031541.202996.png
1305031541.243593 rgb/1305031541.243593.png 1305031541.235198 depth/1305031541.235198.png
1305031541.275691 rgb/1305031541.275691.png 1305031541.267954 depth/1305031541.267954.png
1305031541.307436 rgb/1305031541.307436.png 1305031541.301672 depth/1305031541.301672.png
1305031541.343493 rgb/1305031541.343493.png 1305031541.331852 depth/1305031541.331852.png
1305031541.375507 rgb/1305031541.375507.png 1305031541.371250 depth/1305031541.371250.png
1305031541.407707 rgb/1305031541.407707.png 1305031541.402022 depth/1305031541.402022.png
1305031541.443699 rgb/1305031541.443699.png 1305031541.431932 depth/1305031541.431932.png
1305031541.475389 rgb/1305031541.475389.png 1305031541.471366 depth/1305031541.471366.png
1305031541.507656 rgb/1305031541.507656.png 1305031541.501569 depth/1305031541.501569.png
1305031541.543489 rgb/1305031541.543489.png 1305031541.535345 depth/1305031541.535345.png
1305031541.575608 rgb/1305031541.575608.png 1305031541.569819 depth/1305031541.569819.png
1305031541.607431 rgb/1305031541.607431.png 1305031541.603472 depth/1305031541.603472.png
1305031541.643543 rgb/1305031541.643543.png 1305031541.635279 depth/1305031541.635279.png
1305031541.675424 rgb/1305031541.675424.png 1305031541.671483 depth/1305031541.671483.png
1305031541.707418 rgb/1305031541.707418.png 1305031541.703527 depth/1305031541.703527.png
1305031541.743439 rgb/1305031541.743439.png 1305031541.734963 depth/1305031541.734963.png
1305031541.775415 rgb/1305031541.775415.png 1305031541.771656 depth/1305031541.771656.png
1305031541.807470 rgb/1305031541.807470.png 1305031541.803338 depth/1305031541.803338.png
1305031541.843441 rgb/1305031541.843441.png 1305031541.835259 depth/1305031541.835259.png
1305031541.875438 rgb/1305031541.875438.png 1305031541.871359 depth/1305031541.871359.png
1305031541.907570 rgb/1305031541.907570.png 1305031541.903131 depth/1305031541.903131.png
1305031541.943524 rgb/1305031541.943524.png 1305031541.932460 depth/1305031541.932460.png
1305031541.975524 rgb/1305031541.975524.png 1305031541.969202 depth/1305031541.969202.png
1305031542.007694 rgb/1305031542.007694.png 1305031542.000034 depth/1305031542.000034.png
1305031542.043489 rgb/1305031542.043489.png 1305031542.032795 depth/1305031542.032795.png
1305031542.075555 rgb/1305031542.075555.png 1305031542.069819 depth/1305031542.069819.png
1305031542.107416 rgb/1305031542.107416.png 1305031542.102573 depth/1305031542.102573.png
1305031542.143525 rgb/1305031542.143525.png 1305031542.139294 depth/1305031542.139294.png
1305031542.175524 rgb/1305031542.175524.png 1305031542.170485 depth/1305031542.170485.png
1305031542.207368 rgb/1305031542.207368.png 1305031542.202214 depth/1305031542.202214.png
1305031542.244091 rgb/1305031542.244091.png 1305031542.237243 depth/1305031542.237243.png
1305031542.275425 rgb/1305031542.275425.png 1305031542.269752 depth/1305031542.269752.png
1305031542.307528 rgb/1305031542.307528.png 1305031542.301218 depth/1305031542.301218.png
1305031542.343479 rgb/1305031542.343479.png 1305031542.338812 depth/1305031542.338812.png
1305031542.375553 rgb/1305031542.375553.png 1305031542.371582 depth/1305031542.371582.png
1305031542.407482 rgb/1305031542.407482.png 1305031542.403140 depth/1305031542.403140.png
1305031542.443447 rgb/1305031542.443447.png 1305031542.439210 depth/1305031542.439210.png
1305031542.475446 rgb/1305031542.475446.png 1305031542.471527 depth/1305031542.471527.png
1305031542.507447 rgb/1305031542.507447.png 1305031542.503717 depth/1305031542.503717.png
1305031542.543425 rgb/1305031542.543425.png 1305031542.539439 depth/1305031542.539439.png
1305031542.575428 rgb/1305031542.575428.png 1305031542.571672 depth/1305031542.571672.png
1305031542.607410 rgb/1305031542.607410.png 1305031542.603499 depth/1305031542.603499.png
1305031542.643424 rgb/1305031542.643424.png 1305031542.639171 depth/1305031542.639171.png
1305031542.675341 rgb/1305031542.675341.png 1305031542.668866 depth/1305031542.668866.png
1305031542.707362 rgb/1305031542.707362.png 1305031542.702239 depth/1305031542.702239.png
1305031542.743855 rgb/1305031542.743855.png 1305031542.737961 depth/1305031542.737961.png
1305031542.775624 rgb/1305031542.775624.png 1305031542.771170 depth/1305031542.771170.png
1305031542.807676 rgb/1305031542.807676.png 1305031542.803270 depth/1305031542.803270.png
1305031542.843453 rgb/1305031542.843453.png 1305031542.839568 depth/1305031542.839568.png
1305031542.875473 rgb/1305031542.875473.png 1305031542.871198 depth/1305031542.871198.png
1305031542.907374 rgb/1305031542.907374.png 1305031542.903732 depth/1305031542.903732.png
1305031542.943449 rgb/1305031542.943449.png 1305031542.939215 depth/1305031542.939215.png
1305031542.975416 rgb/1305031542.975416.png 1305031542.970866 depth/1305031542.970866.png
1305031543.007462 rgb/1305031543.007462.png 1305031543.002677 depth/1305031543.002677.png
1305031543.043546 rgb/1305031543.043546.png 1305031543.039126 depth/1305031543.039126.png
1305031543.075465 rgb/1305031543.075465.png 1305031543.070710 depth/1305031543.070710.png
1305031543.107471 rgb/1305031543.107471.png 1305031543.102755 depth/1305031543.102755.png
1305031543.143424 rgb/1305031543.143424.png 1305031543.139358 depth/1305031543.139358.png
1305031543.175587 rgb/1305031543.175587.png 1305031543.170265 depth/1305031543.170265.png
1305031543.207464 rgb/1305031543.207464.png 1305031543.200190 depth/1305031543.200190.png
1305031543.243490 rgb/1305031543.243490.png 1305031543.238701 depth/1305031543.238701.png
1305031543.275504 rgb/1305031543.275504.png 1305031543.270923 depth/1305031543.270923.png
1305031543.307391 rgb/1305031543.307391.png 1305031543.302962 depth/1305031543.302962.png
1305031543.343502 rgb/1305031543.343502.png 1305031543.338824 depth/1305031543.338824.png
1305031543.375520 rgb/1305031543.375520.png 1305031543.370800 depth/1305031543.370800.png
1305031543.407575 rgb/1305031543.407575.png 1305031543.407586 depth/1305031543.407586.png
1305031543.443593 rgb/1305031543.443593.png 1305031543.436408 depth/1305031543.436408.png
1305031543.475420 rgb/1305031543.475420.png 1305031543.472193 depth/1305031543.472193.png
1305031543.507652 rgb/1305031543.507652.png 1305031543.507662 depth/1305031543.507662.png
1305031543.543433 rgb/1305031543.543433.png 1305031543.539811 depth/1305031543.539811.png
1305031543.575393 rgb/1305031543.575393.png 1305031543.572301 depth/1305031543.572301.png
1305031543.607524 rgb/1305031543.607524.png 1305031543.607686 depth/1305031543.607686.png
1305031543.643400 rgb/1305031543.643400.png 1305031543.639875 depth/1305031543.639875.png
1305031543.675460 rgb/1305031543.675460.png 1305031543.671696 depth/1305031543.671696.png
1305031543.707478 rgb/1305031543.707478.png 1305031543.707488 depth/1305031543.707488.png
1305031543.743399 rgb/1305031543.743399.png 1305031543.739759 depth/1305031543.739759.png
1305031543.775642 rgb/1305031543.775642.png 1305031543.771875 depth/1305031543.771875.png
1305031543.807514 rgb/1305031543.807514.png 1305031543.807535 depth/1305031543.807535.png
1305031543.843406 rgb/1305031543.843406.png 1305031543.839894 depth/1305031543.839894.png
1305031543.875410 rgb/1305031543.875410.png 1305031543.871869 depth/1305031543.871869.png
1305031543.907459 rgb/1305031543.907459.png 1305031543.907474 depth/1305031543.907474.png
1305031543.943413 rgb/1305031543.943413.png 1305031543.939753 depth/1305031543.939753.png
1305031543.975473 rgb/1305031543.975473.png 1305031543.970786 depth/1305031543.970786.png
1305031544.007491 rgb/1305031544.007491.png 1305031544.007529 depth/1305031544.007529.png
1305031544.043491 rgb/1305031544.043491.png 1305031544.038948 depth/1305031544.038948.png
1305031544.075509 rgb/1305031544.075509.png 1305031544.070711 depth/1305031544.070711.png
1305031544.107376 rgb/1305031544.107376.png 1305031544.106609 depth/1305031544.106609.png
1305031544.143795 rgb/1305031544.143795.png 1305031544.137311 depth/1305031544.137311.png
1305031544.175829 rgb/1305031544.175829.png 1305031544.171722 depth/1305031544.171722.png
1305031544.207354 rgb/1305031544.207354.png 1305031544.206571 depth/1305031544.206571.png
1305031544.243427 rgb/1305031544.243427.png 1305031544.238072 depth/1305031544.238072.png
1305031544.275540 rgb/1305031544.275540.png 1305031544.267766 depth/1305031544.267766.png
1305031544.307370 rgb/1305031544.307370.png 1305031544.303584 depth/1305031544.303584.png
1305031544.343409 rgb/1305031544.343409.png 1305031544.338210 depth/1305031544.338210.png
1305031544.375459 rgb/1305031544.375459.png 1305031544.367911 depth/1305031544.367911.png
1305031544.407333 rgb/1305031544.407333.png 1305031544.405875 depth/1305031544.405875.png
1305031544.443375 rgb/1305031544.443375.png 1305031544.437826 depth/1305031544.437826.png
1305031544.475427 rgb/1305031544.475427.png 1305031544.469937 depth/1305031544.469937.png
1305031544.507367 rgb/1305031544.507367.png 1305031544.505986 depth/1305031544.505986.png
1305031544.543416 rgb/1305031544.543416.png 1305031544.539003 depth/1305031544.539003.png
1305031544.575497 rgb/1305031544.575497.png 1305031544.574785 depth/1305031544.574785.png
1305031544.607409 rgb/1305031544.607409.png 1305031544.607438 depth/1305031544.607438.png
1305031544.643444 rgb/1305031544.643444.png 1305031544.638925 depth/1305031544.638925.png
1305031544.675586 rgb/1305031544.675586.png 1305031544.675602 depth/1305031544.675602.png
1305031544.707411 rgb/1305031544.707411.png 1305031544.703615 depth/1305031544.703615.png
1305031544.743438 rgb/1305031544.743438.png 1305031544.738977 depth/1305031544.738977.png
1305031544.775418 rgb/1305031544.775418.png 1305031544.775192 depth/1305031544.775192.png
1305031544.807397 rgb/1305031544.807397.png 1305031544.807101 depth/1305031544.807101.png
1305031544.843491 rgb/1305031544.843491.png 1305031544.839027 depth/1305031544.839027.png
1305031544.875360 rgb/1305031544.875360.png 1305031544.875379 depth/1305031544.875379.png
1305031544.907423 rgb/1305031544.907423.png 1305031544.907436 depth/1305031544.907436.png
1305031544.943434 rgb/1305031544.943434.png 1305031544.939009 depth/1305031544.939009.png
1305031544.975537 rgb/1305031544.975537.png 1305031544.975561 depth/1305031544.975561.png
1305031545.007393 rgb/1305031545.007393.png 1305031545.007409 depth/1305031545.007409.png
1305031545.043477 rgb/1305031545.043477.png 1305031545.039484 depth/1305031545.039484.png
1305031545.075369 rgb/1305031545.075369.png 1305031545.075213 depth/1305031545.075213.png
1305031545.107399 rgb/1305031545.107399.png 1305031545.107171 depth/1305031545.107171.png
1305031545.144171 rgb/1305031545.144171.png 1305031545.139414 depth/1305031545.139414.png
1305031545.175406 rgb/1305031545.175406.png 1305031545.174984 depth/1305031545.174984.png
1305031545.207577 rgb/1305031545.207577.png 1305031545.207672 depth/1305031545.207672.png
1305031545.243483 rgb/1305031545.243483.png 1305031545.239686 depth/1305031545.239686.png
1305031545.275369 rgb/1305031545.275369.png 1305031545.275412 depth/1305031545.275412.png
1305031545.307451 rgb/1305031545.307451.png 1305031545.306213 depth/1305031545.306213.png
1305031545.343494 rgb/1305031545.343494.png 1305031545.339544 depth/1305031545.339544.png
1305031545.375545 rgb/1305031545.375545.png 1305031545.375555 depth/1305031545.375555.png
1305031545.407452 rgb/1305031545.407452.png 1305031545.407463 depth/1305031545.407463.png
1305031545.444180 rgb/1305031545.444180.png 1305031545.439168 depth/1305031545.439168.png
1305031545.475423 rgb/1305031545.475423.png 1305031545.475453 depth/1305031545.475453.png
1305031545.507394 rgb/1305031545.507394.png 1305031545.507417 depth/1305031545.507417.png
1305031545.543418 rgb/1305031545.543418.png 1305031545.539498 depth/1305031545.539498.png
1305031545.578078 rgb/1305031545.578078.png 1305031545.578088 depth/1305031545.578088.png
1305031545.607417 rgb/1305031545.607417.png 1305031545.603778 depth/1305031545.603778.png
1305031545.643463 rgb/1305031545.643463.png 1305031545.635945 depth/1305031545.635945.png
1305031545.675289 rgb/1305031545.675289.png 1305031545.673535 depth/1305031545.673535.png
1305031545.707398 rgb/1305031545.707398.png 1305031545.706561 depth/1305031545.706561.png
1305031545.743570 rgb/1305031545.743570.png 1305031545.739007 depth/1305031545.739007.png
1305031545.775452 rgb/1305031545.775452.png 1305031545.775565 depth/1305031545.775565.png
1305031545.807404 rgb/1305031545.807404.png 1305031545.807492 depth/1305031545.807492.png
1305031545.843376 rgb/1305031545.843376.png 1305031545.843386 depth/1305031545.843386.png
1305031545.875537 rgb/1305031545.875537.png 1305031545.875515 depth/1305031545.875515.png
1305031545.907389 rgb/1305031545.907389.png 1305031545.907616 depth/1305031545.907616.png
1305031545.943457 rgb/1305031545.943457.png 1305031545.943703 depth/1305031545.943703.png
1305031545.975621 rgb/1305031545.975621.png 1305031545.975685 depth/1305031545.975685.png
1305031546.007516 rgb/1305031546.007516.png 1305031546.007570 depth/1305031546.007570.png
1305031546.043769 rgb/1305031546.043769.png 1305031546.043793 depth/1305031546.043793.png
1305031546.075414 rgb/1305031546.075414.png 1305031546.075425 depth/1305031546.075425.png
1305031546.107395 rgb/1305031546.107395.png 1305031546.104074 depth/1305031546.104074.png
1305031546.143502 rgb/1305031546.143502.png 1305031546.143517 depth/1305031546.143517.png
1305031546.175952 rgb/1305031546.175952.png 1305031546.175972 depth/1305031546.175972.png
1305031546.207500 rgb/1305031546.207500.png 1305031546.207525 depth/1305031546.207525.png
1305031546.243551 rgb/1305031546.243551.png 1305031546.243573 depth/1305031546.243573.png
1305031546.276098 rgb/1305031546.276098.png 1305031546.276113 depth/1305031546.276113.png
1305031546.308110 rgb/1305031546.308110.png 1305031546.308117 depth/1305031546.308117.png
1305031546.343919 rgb/1305031546.343919.png 1305031546.343932 depth/1305031546.343932.png
1305031546.376056 rgb/1305031546.376056.png 1305031546.376105 depth/1305031546.376105.png
1305031546.407659 rgb/1305031546.407659.png 1305031546.407683 depth/1305031546.407683.png
1305031546.443968 rgb/1305031546.443968.png 1305031546.443985 depth/1305031546.443985.png
1305031546.475996 rgb/1305031546.475996.png 1305031546.476002 depth/1305031546.476002.png
1305031546.507967 rgb/1305031546.507967.png 1305031546.507978 depth/1305031546.507978.png
1305031546.544068 rgb/1305031546.544068.png 1305031546.544091 depth/1305031546.544091.png
1305031546.576412 rgb/1305031546.576412.png 1305031546.576436 depth/1305031546.576436.png
1305031546.607717 rgb/1305031546.607717.png 1305031546.604477 depth/1305031546.604477.png
1305031546.644200 rgb/1305031546.644200.png 1305031546.644231 depth/1305031546.644231.png
1305031546.676003 rgb/1305031546.676003.png 1305031546.676019 depth/1305031546.676019.png
1305031546.707934 rgb/1305031546.707934.png 1305031546.707952 depth/1305031546.707952.png
1305031546.743887 rgb/1305031546.743887.png 1305031546.743907 depth/1305031546.743907.png
1305031546.775864 rgb/1305031546.775864.png 1305031546.775885 depth/1305031546.775885.png
1305031546.807996 rgb/1305031546.807996.png 1305031546.808019 depth/1305031546.808019.png
1305031546.844079 rgb/1305031546.844079.png 1305031546.844098 depth/1305031546.844098.png
1305031546.876064 rgb/1305031546.876064.png 1305031546.876150 depth/1305031546.876150.png
1305031546.907783 rgb/1305031546.907783.png 1305031546.904254 depth/1305031546.904254.png
1305031546.943858 rgb/1305031546.943858.png 1305031546.943871 depth/1305031546.943871.png
1305031546.975884 rgb/1305031546.975884.png 1305031546.975693 depth/1305031546.975693.png
1305031547.011984 rgb/1305031547.011984.png 1305031547.008548 depth/1305031547.008548.png
1305031547.044214 rgb/1305031547.044214.png 1305031547.044236 depth/1305031547.044236.png
1305031547.076346 rgb/1305031547.076346.png 1305031547.074033 depth/1305031547.074033.png
1305031547.111991 rgb/1305031547.111991.png 1305031547.109368 depth/1305031547.109368.png
1305031547.144071 rgb/1305031547.144071.png 1305031547.143020 depth/1305031547.143020.png
1305031547.175909 rgb/1305031547.175909.png 1305031547.172567 depth/1305031547.172567.png
1305031547.211964 rgb/1305031547.211964.png 1305031547.211605 depth/1305031547.211605.png
1305031547.244113 rgb/1305031547.244113.png 1305031547.244133 depth/1305031547.244133.png
1305031547.276546 rgb/1305031547.276546.png 1305031547.276566 depth/1305031547.276566.png
1305031547.312261 rgb/1305031547.312261.png 1305031547.312300 depth/1305031547.312300.png
1305031547.344192 rgb/1305031547.344192.png 1305031547.344201 depth/1305031547.344201.png
1305031547.376753 rgb/1305031547.376753.png 1305031547.376783 depth/1305031547.376783.png
1305031547.412260 rgb/1305031547.412260.png 1305031547.412309 depth/1305031547.412309.png
1305031547.444472 rgb/1305031547.444472.png 1305031547.444479 depth/1305031547.444479.png
1305031547.476347 rgb/1305031547.476347.png 1305031547.475653 depth/1305031547.475653.png
1305031547.512114 rgb/1305031547.512114.png 1305031547.512129 depth/1305031547.512129.png
1305031547.544015 rgb/1305031547.544015.png 1305031547.543063 depth/1305031547.543063.png
1305031547.576437 rgb/1305031547.576437.png 1305031547.572452 depth/1305031547.572452.png
1305031547.612296 rgb/1305031547.612296.png 1305031547.610069 depth/1305031547.610069.png
1305031547.644160 rgb/1305031547.644160.png 1305031547.643685 depth/1305031547.643685.png
1305031547.677287 rgb/1305031547.677287.png 1305031547.675727 depth/1305031547.675727.png
1305031547.712338 rgb/1305031547.712338.png 1305031547.712359 depth/1305031547.712359.png
1305031547.744332 rgb/1305031547.744332.png 1305031547.741819 depth/1305031547.741819.png
1305031547.776390 rgb/1305031547.776390.png 1305031547.773659 depth/1305031547.773659.png
1305031547.812317 rgb/1305031547.812317.png 1305031547.812136 depth/1305031547.812136.png
1305031547.844564 rgb/1305031547.844564.png 1305031547.844573 depth/1305031547.844573.png
1305031547.876362 rgb/1305031547.876362.png 1305031547.875313 depth/1305031547.875313.png
1305031547.912744 rgb/1305031547.912744.png 1305031547.912229 depth/1305031547.912229.png
1305031547.944304 rgb/1305031547.944304.png 1305031547.942674 depth/1305031547.942674.png
1305031547.976482 rgb/1305031547.976482.png 1305031547.976525 depth/1305031547.976525.png
================================================
FILE: Examples/RGB-D/associations/fr1_room.txt
================================================
1305031910.765238 rgb/1305031910.765238.png 1305031910.771502 depth/1305031910.771502.png
1305031910.797230 rgb/1305031910.797230.png 1305031910.803249 depth/1305031910.803249.png
1305031910.835208 rgb/1305031910.835208.png 1305031910.835215 depth/1305031910.835215.png
1305031910.865025 rgb/1305031910.865025.png 1305031910.871167 depth/1305031910.871167.png
1305031910.897222 rgb/1305031910.897222.png 1305031910.903682 depth/1305031910.903682.png
1305031910.935211 rgb/1305031910.935211.png 1305031910.935221 depth/1305031910.935221.png
1305031910.965249 rgb/1305031910.965249.png 1305031910.971338 depth/1305031910.971338.png
1305031910.997325 rgb/1305031910.997325.png 1305031911.003202 depth/1305031911.003202.png
1305031911.035050 rgb/1305031911.035050.png 1305031911.035056 depth/1305031911.035056.png
1305031911.065269 rgb/1305031911.065269.png 1305031911.074509 depth/1305031911.074509.png
1305031911.097196 rgb/1305031911.097196.png 1305031911.103332 depth/1305031911.103332.png
1305031911.135664 rgb/1305031911.135664.png 1305031911.135683 depth/1305031911.135683.png
1305031911.165177 rgb/1305031911.165177.png 1305031911.171831 depth/1305031911.171831.png
1305031911.197213 rgb/1305031911.197213.png 1305031911.207568 depth/1305031911.207568.png
1305031911.235651 rgb/1305031911.235651.png 1305031911.235660 depth/1305031911.235660.png
1305031911.265104 rgb/1305031911.265104.png 1305031911.268497 depth/1305031911.268497.png
1305031911.297334 rgb/1305031911.297334.png 1305031911.303504 depth/1305031911.303504.png
1305031911.333191 rgb/1305031911.333191.png 1305031911.339412 depth/1305031911.339412.png
1305031911.365235 rgb/1305031911.365235.png 1305031911.371631 depth/1305031911.371631.png
1305031911.397333 rgb/1305031911.397333.png 1305031911.403484 depth/1305031911.403484.png
1305031911.433256 rgb/1305031911.433256.png 1305031911.439656 depth/1305031911.439656.png
1305031911.465250 rgb/1305031911.465250.png 1305031911.471398 depth/1305031911.471398.png
1305031911.497291 rgb/1305031911.497291.png 1305031911.503476 depth/1305031911.503476.png
1305031911.533251 rgb/1305031911.533251.png 1305031911.539636 depth/1305031911.539636.png
1305031911.565335 rgb/1305031911.565335.png 1305031911.571543 depth/1305031911.571543.png
1305031911.597302 rgb/1305031911.597302.png 1305031911.603617 depth/1305031911.603617.png
1305031911.633337 rgb/1305031911.633337.png 1305031911.639562 depth/1305031911.639562.png
1305031911.665124 rgb/1305031911.665124.png 1305031911.671469 depth/1305031911.671469.png
1305031911.697167 rgb/1305031911.697167.png 1305031911.705153 depth/1305031911.705153.png
1305031911.733203 rgb/1305031911.733203.png 1305031911.739460 depth/1305031911.739460.png
1305031911.765284 rgb/1305031911.765284.png 1305031911.771372 depth/1305031911.771372.png
1305031911.797297 rgb/1305031911.797297.png 1305031911.803540 depth/1305031911.803540.png
1305031911.833338 rgb/1305031911.833338.png 1305031911.839611 depth/1305031911.839611.png
1305031911.865269 rgb/1305031911.865269.png 1305031911.871650 depth/1305031911.871650.png
1305031911.897159 rgb/1305031911.897159.png 1305031911.904281 depth/1305031911.904281.png
1305031911.933063 rgb/1305031911.933063.png 1305031911.940338 depth/1305031911.940338.png
1305031911.965140 rgb/1305031911.965140.png 1305031911.972044 depth/1305031911.972044.png
1305031911.997252 rgb/1305031911.997252.png 1305031912.004430 depth/1305031912.004430.png
1305031912.033135 rgb/1305031912.033135.png 1305031912.040573 depth/1305031912.040573.png
1305031912.065365 rgb/1305031912.065365.png 1305031912.069771 depth/1305031912.069771.png
1305031912.096953 rgb/1305031912.096953.png 1305031912.104327 depth/1305031912.104327.png
1305031912.133282 rgb/1305031912.133282.png 1305031912.139831 depth/1305031912.139831.png
1305031912.165138 rgb/1305031912.165138.png 1305031912.171439 depth/1305031912.171439.png
1305031912.197357 rgb/1305031912.197357.png 1305031912.204109 depth/1305031912.204109.png
1305031912.233265 rgb/1305031912.233265.png 1305031912.239820 depth/1305031912.239820.png
1305031912.265090 rgb/1305031912.265090.png 1305031912.272101 depth/1305031912.272101.png
1305031912.297250 rgb/1305031912.297250.png 1305031912.303877 depth/1305031912.303877.png
1305031912.333274 rgb/1305031912.333274.png 1305031912.340453 depth/1305031912.340453.png
1305031912.365250 rgb/1305031912.365250.png 1305031912.371540 depth/1305031912.371540.png
1305031912.397198 rgb/1305031912.397198.png 1305031912.403793 depth/1305031912.403793.png
1305031912.433290 rgb/1305031912.433290.png 1305031912.438048 depth/1305031912.438048.png
1305031912.465142 rgb/1305031912.465142.png 1305031912.472320 depth/1305031912.472320.png
1305031912.497123 rgb/1305031912.497123.png 1305031912.508934 depth/1305031912.508934.png
1305031912.533113 rgb/1305031912.533113.png 1305031912.540326 depth/1305031912.540326.png
1305031912.565146 rgb/1305031912.565146.png 1305031912.572025 depth/1305031912.572025.png
1305031912.597090 rgb/1305031912.597090.png 1305031912.607722 depth/1305031912.607722.png
1305031912.633132 rgb/1305031912.633132.png 1305031912.637657 depth/1305031912.637657.png
1305031912.665220 rgb/1305031912.665220.png 1305031912.672091 depth/1305031912.672091.png
1305031912.697182 rgb/1305031912.697182.png 1305031912.708413 depth/1305031912.708413.png
1305031912.733125 rgb/1305031912.733125.png 1305031912.740310 depth/1305031912.740310.png
1305031912.765193 rgb/1305031912.765193.png 1305031912.772223 depth/1305031912.772223.png
1305031912.797155 rgb/1305031912.797155.png 1305031912.809603 depth/1305031912.809603.png
1305031912.833077 rgb/1305031912.833077.png 1305031912.840573 depth/1305031912.840573.png
1305031912.865153 rgb/1305031912.865153.png 1305031912.872087 depth/1305031912.872087.png
1305031912.897198 rgb/1305031912.897198.png 1305031912.908080 depth/1305031912.908080.png
1305031912.933115 rgb/1305031912.933115.png 1305031912.940609 depth/1305031912.940609.png
1305031912.965034 rgb/1305031912.965034.png 1305031912.972119 depth/1305031912.972119.png
1305031912.997049 rgb/1305031912.997049.png 1305031913.008923 depth/1305031913.008923.png
1305031913.033133 rgb/1305031913.033133.png 1305031913.040171 depth/1305031913.040171.png
1305031913.065209 rgb/1305031913.065209.png 1305031913.072194 depth/1305031913.072194.png
1305031913.097038 rgb/1305031913.097038.png 1305031913.108367 depth/1305031913.108367.png
1305031913.133146 rgb/1305031913.133146.png 1305031913.137597 depth/1305031913.137597.png
1305031913.165211 rgb/1305031913.165211.png 1305031913.172328 depth/1305031913.172328.png
1305031913.197113 rgb/1305031913.197113.png 1305031913.208546 depth/1305031913.208546.png
1305031913.233126 rgb/1305031913.233126.png 1305031913.240453 depth/1305031913.240453.png
1305031913.265022 rgb/1305031913.265022.png 1305031913.272069 depth/1305031913.272069.png
1305031913.297160 rgb/1305031913.297160.png 1305031913.308747 depth/1305031913.308747.png
1305031913.333122 rgb/1305031913.333122.png 1305031913.340047 depth/1305031913.340047.png
1305031913.365070 rgb/1305031913.365070.png 1305031913.372117 depth/1305031913.372117.png
1305031913.397099 rgb/1305031913.397099.png 1305031913.408181 depth/1305031913.408181.png
1305031913.433081 rgb/1305031913.433081.png 1305031913.440305 depth/1305031913.440305.png
1305031913.465231 rgb/1305031913.465231.png 1305031913.472064 depth/1305031913.472064.png
1305031913.497227 rgb/1305031913.497227.png 1305031913.508406 depth/1305031913.508406.png
1305031913.533297 rgb/1305031913.533297.png 1305031913.538696 depth/1305031913.538696.png
1305031913.565261 rgb/1305031913.565261.png 1305031913.568481 depth/1305031913.568481.png
1305031913.597139 rgb/1305031913.597139.png 1305031913.607051 depth/1305031913.607051.png
1305031913.633293 rgb/1305031913.633293.png 1305031913.637112 depth/1305031913.637112.png
1305031913.665421 rgb/1305031913.665421.png 1305031913.671418 depth/1305031913.671418.png
1305031913.697243 rgb/1305031913.697243.png 1305031913.709971 depth/1305031913.709971.png
1305031913.733097 rgb/1305031913.733097.png 1305031913.743396 depth/1305031913.743396.png
1305031913.765028 rgb/1305031913.765028.png 1305031913.778085 depth/1305031913.778085.png
1305031913.797106 rgb/1305031913.797106.png 1305031913.809508 depth/1305031913.809508.png
1305031913.833143 rgb/1305031913.833143.png 1305031913.840405 depth/1305031913.840405.png
1305031913.865063 rgb/1305031913.865063.png 1305031913.876025 depth/1305031913.876025.png
1305031913.897116 rgb/1305031913.897116.png 1305031913.908138 depth/1305031913.908138.png
1305031913.933123 rgb/1305031913.933123.png 1305031913.939898 depth/1305031913.939898.png
1305031913.965134 rgb/1305031913.965134.png 1305031913.977474 depth/1305031913.977474.png
1305031913.997116 rgb/1305031913.997116.png 1305031914.008756 depth/1305031914.008756.png
1305031914.033441 rgb/1305031914.033441.png 1305031914.042148 depth/1305031914.042148.png
1305031914.065072 rgb/1305031914.065072.png 1305031914.075482 depth/1305031914.075482.png
1305031914.097126 rgb/1305031914.097126.png 1305031914.108031 depth/1305031914.108031.png
1305031914.133245 rgb/1305031914.133245.png 1305031914.142725 depth/1305031914.142725.png
1305031914.165013 rgb/1305031914.165013.png 1305031914.177921 depth/1305031914.177921.png
1305031914.197110 rgb/1305031914.197110.png 1305031914.207783 depth/1305031914.207783.png
1305031914.233108 rgb/1305031914.233108.png 1305031914.239738 depth/1305031914.239738.png
1305031914.265074 rgb/1305031914.265074.png 1305031914.275498 depth/1305031914.275498.png
1305031914.297165 rgb/1305031914.297165.png 1305031914.307439 depth/1305031914.307439.png
1305031914.333148 rgb/1305031914.333148.png 1305031914.339813 depth/1305031914.339813.png
1305031914.365058 rgb/1305031914.365058.png 1305031914.376077 depth/1305031914.376077.png
1305031914.397215 rgb/1305031914.397215.png 1305031914.407339 depth/1305031914.407339.png
1305031914.433060 rgb/1305031914.433060.png 1305031914.439366 depth/1305031914.439366.png
1305031914.465054 rgb/1305031914.465054.png 1305031914.475929 depth/1305031914.475929.png
1305031914.497127 rgb/1305031914.497127.png 1305031914.508084 depth/1305031914.508084.png
1305031914.533107 rgb/1305031914.533107.png 1305031914.539445 depth/1305031914.539445.png
1305031914.565001 rgb/1305031914.565001.png 1305031914.575638 depth/1305031914.575638.png
1305031914.597122 rgb/1305031914.597122.png 1305031914.607525 depth/1305031914.607525.png
1305031914.633055 rgb/1305031914.633055.png 1305031914.639613 depth/1305031914.639613.png
1305031914.665019 rgb/1305031914.665019.png 1305031914.675447 depth/1305031914.675447.png
1305031914.697129 rgb/1305031914.697129.png 1305031914.707659 depth/1305031914.707659.png
1305031914.733078 rgb/1305031914.733078.png 1305031914.742851 depth/1305031914.742851.png
1305031914.764901 rgb/1305031914.764901.png 1305031914.776080 depth/1305031914.776080.png
1305031914.797119 rgb/1305031914.797119.png 1305031914.810077 depth/1305031914.810077.png
1305031914.833133 rgb/1305031914.833133.png 1305031914.839826 depth/1305031914.839826.png
1305031914.865128 rgb/1305031914.865128.png 1305031914.876190 depth/1305031914.876190.png
1305031914.897188 rgb/1305031914.897188.png 1305031914.908910 depth/1305031914.908910.png
1305031914.933099 rgb/1305031914.933099.png 1305031914.938404 depth/1305031914.938404.png
1305031914.964978 rgb/1305031914.964978.png 1305031914.975628 depth/1305031914.975628.png
1305031914.997078 rgb/1305031914.997078.png 1305031915.007678 depth/1305031915.007678.png
1305031915.033152 rgb/1305031915.033152.png 1305031915.044015 depth/1305031915.044015.png
1305031915.065009 rgb/1305031915.065009.png 1305031915.073665 depth/1305031915.073665.png
1305031915.097024 rgb/1305031915.097024.png 1305031915.105907 depth/1305031915.105907.png
1305031915.133208 rgb/1305031915.133208.png 1305031915.142313 depth/1305031915.142313.png
1305031915.165021 rgb/1305031915.165021.png 1305031915.173454 depth/1305031915.173454.png
1305031915.197108 rgb/1305031915.197108.png 1305031915.209278 depth/1305031915.209278.png
1305031915.233111 rgb/1305031915.233111.png 1305031915.244223 depth/1305031915.244223.png
1305031915.264979 rgb/1305031915.264979.png 1305031915.276431 depth/1305031915.276431.png
1305031915.297152 rgb/1305031915.297152.png 1305031915.306226 depth/1305031915.306226.png
1305031915.333207 rgb/1305031915.333207.png 1305031915.341488 depth/1305031915.341488.png
1305031915.365050 rgb/1305031915.365050.png 1305031915.373270 depth/1305031915.373270.png
1305031915.397167 rgb/1305031915.397167.png 1305031915.406736 depth/1305031915.406736.png
1305031915.432960 rgb/1305031915.432960.png 1305031915.442726 depth/1305031915.442726.png
1305031915.464920 rgb/1305031915.464920.png 1305031915.474257 depth/1305031915.474257.png
1305031915.497121 rgb/1305031915.497121.png 1305031915.506429 depth/1305031915.506429.png
1305031915.533058 rgb/1305031915.533058.png 1305031915.542700 depth/1305031915.542700.png
1305031915.564985 rgb/1305031915.564985.png 1305031915.575890 depth/1305031915.575890.png
1305031915.601161 rgb/1305031915.601161.png 1305031915.607095 depth/1305031915.607095.png
1305031915.633062 rgb/1305031915.633062.png 1305031915.644456 depth/1305031915.644456.png
1305031915.665003 rgb/1305031915.665003.png 1305031915.676911 depth/1305031915.676911.png
1305031915.701106 rgb/1305031915.701106.png 1305031915.710920 depth/1305031915.710920.png
1305031915.733046 rgb/1305031915.733046.png 1305031915.744275 depth/1305031915.744275.png
1305031915.765010 rgb/1305031915.765010.png 1305031915.776046 depth/1305031915.776046.png
1305031915.801243 rgb/1305031915.801243.png 1305031915.807068 depth/1305031915.807068.png
1305031915.833049 rgb/1305031915.833049.png 1305031915.844882 depth/1305031915.844882.png
1305031915.865069 rgb/1305031915.865069.png 1305031915.877002 depth/1305031915.877002.png
1305031915.901234 rgb/1305031915.901234.png 1305031915.907069 depth/1305031915.907069.png
1305031915.933056 rgb/1305031915.933056.png 1305031915.944991 depth/1305031915.944991.png
1305031915.965061 rgb/1305031915.965061.png 1305031915.976975 depth/1305031915.976975.png
1305031916.001234 rgb/1305031916.001234.png 1305031916.007650 depth/1305031916.007650.png
1305031916.033043 rgb/1305031916.033043.png 1305031916.044257 depth/1305031916.044257.png
1305031916.065060 rgb/1305031916.065060.png 1305031916.075852 depth/1305031916.075852.png
1305031916.101115 rgb/1305031916.101115.png 1305031916.107904 depth/1305031916.107904.png
1305031916.133093 rgb/1305031916.133093.png 1305031916.143770 depth/1305031916.143770.png
1305031916.165155 rgb/1305031916.165155.png 1305031916.175966 depth/1305031916.175966.png
1305031916.201031 rgb/1305031916.201031.png 1305031916.213438 depth/1305031916.213438.png
1305031916.233050 rgb/1305031916.233050.png 1305031916.244817 depth/1305031916.244817.png
1305031916.265060 rgb/1305031916.265060.png 1305031916.276150 depth/1305031916.276150.png
1305031916.301076 rgb/1305031916.301076.png 1305031916.312024 depth/1305031916.312024.png
1305031916.333426 rgb/1305031916.333426.png 1305031916.344853 depth/1305031916.344853.png
1305031916.365121 rgb/1305031916.365121.png 1305031916.375943 depth/1305031916.375943.png
1305031916.401006 rgb/1305031916.401006.png 1305031916.412634 depth/1305031916.412634.png
1305031916.433168 rgb/1305031916.433168.png 1305031916.445160 depth/1305031916.445160.png
1305031916.465124 rgb/1305031916.465124.png 1305031916.475799 depth/1305031916.475799.png
1305031916.501025 rgb/1305031916.501025.png 1305031916.511070 depth/1305031916.511070.png
1305031916.533266 rgb/1305031916.533266.png 1305031916.542416 depth/1305031916.542416.png
1305031916.565142 rgb/1305031916.565142.png 1305031916.574661 depth/1305031916.574661.png
1305031916.601238 rgb/1305031916.601238.png 1305031916.610788 depth/1305031916.610788.png
1305031916.633156 rgb/1305031916.633156.png 1305031916.643191 depth/1305031916.643191.png
1305031916.665139 rgb/1305031916.665139.png 1305031916.674514 depth/1305031916.674514.png
1305031916.701048 rgb/1305031916.701048.png 1305031916.711186 depth/1305031916.711186.png
1305031916.733056 rgb/1305031916.733056.png 1305031916.742388 depth/1305031916.742388.png
1305031916.765076 rgb/1305031916.765076.png 1305031916.774484 depth/1305031916.774484.png
1305031916.801088 rgb/1305031916.801088.png 1305031916.810984 depth/1305031916.810984.png
1305031916.833266 rgb/1305031916.833266.png 1305031916.842413 depth/1305031916.842413.png
1305031916.865085 rgb/1305031916.865085.png 1305031916.874597 depth/1305031916.874597.png
1305031916.901017 rgb/1305031916.901017.png 1305031916.911349 depth/1305031916.911349.png
1305031916.933088 rgb/1305031916.933088.png 1305031916.942991 depth/1305031916.942991.png
1305031916.965054 rgb/1305031916.965054.png 1305031916.975281 depth/1305031916.975281.png
1305031917.001132 rgb/1305031917.001132.png 1305031917.013257 depth/1305031917.013257.png
1305031917.033155 rgb/1305031917.033155.png 1305031917.045346 depth/1305031917.045346.png
1305031917.065136 rgb/1305031917.065136.png 1305031917.078672 depth/1305031917.078672.png
1305031917.101130 rgb/1305031917.101130.png 1305031917.112392 depth/1305031917.112392.png
1305031917.133106 rgb/1305031917.133106.png 1305031917.144721 depth/1305031917.144721.png
1305031917.165045 rgb/1305031917.165045.png 1305031917.175617 depth/1305031917.175617.png
1305031917.201175 rgb/1305031917.201175.png 1305031917.211105 depth/1305031917.211105.png
1305031917.233102 rgb/1305031917.233102.png 1305031917.242019 depth/1305031917.242019.png
1305031917.265163 rgb/1305031917.265163.png 1305031917.275690 depth/1305031917.275690.png
1305031917.301107 rgb/1305031917.301107.png 1305031917.311009 depth/1305031917.311009.png
1305031917.333229 rgb/1305031917.333229.png 1305031917.342994 depth/1305031917.342994.png
1305031917.365138 rgb/1305031917.365138.png 1305031917.375028 depth/1305031917.375028.png
1305031917.401065 rgb/1305031917.401065.png 1305031917.412516 depth/1305031917.412516.png
1305031917.433141 rgb/1305031917.433141.png 1305031917.442191 depth/1305031917.442191.png
1305031917.465076 rgb/1305031917.465076.png 1305031917.480876 depth/1305031917.480876.png
1305031917.501158 rgb/1305031917.501158.png 1305031917.512902 depth/1305031917.512902.png
1305031917.533057 rgb/1305031917.533057.png 1305031917.544881 depth/1305031917.544881.png
1305031917.565195 rgb/1305031917.565195.png 1305031917.581189 depth/1305031917.581189.png
1305031917.601069 rgb/1305031917.601069.png 1305031917.611278 depth/1305031917.611278.png
1305031917.633090 rgb/1305031917.633090.png 1305031917.644587 depth/1305031917.644587.png
1305031917.665060 rgb/1305031917.665060.png 1305031917.680182 depth/1305031917.680182.png
1305031917.701096 rgb/1305031917.701096.png 1305031917.712747 depth/1305031917.712747.png
1305031917.733003 rgb/1305031917.733003.png 1305031917.743645 depth/1305031917.743645.png
1305031917.765114 rgb/1305031917.765114.png 1305031917.776958 depth/1305031917.776958.png
1305031917.801048 rgb/1305031917.801048.png 1305031917.812348 depth/1305031917.812348.png
1305031917.833090 rgb/1305031917.833090.png 1305031917.844755 depth/1305031917.844755.png
1305031917.865107 rgb/1305031917.865107.png 1305031917.879431 depth/1305031917.879431.png
1305031917.901060 rgb/1305031917.901060.png 1305031917.907881 depth/1305031917.907881.png
1305031917.932948 rgb/1305031917.932948.png 1305031917.941261 depth/1305031917.941261.png
1305031917.965346 rgb/1305031917.965346.png 1305031917.978906 depth/1305031917.978906.png
1305031918.001098 rgb/1305031918.001098.png 1305031918.011404 depth/1305031918.011404.png
1305031918.033144 rgb/1305031918.033144.png 1305031918.044049 depth/1305031918.044049.png
1305031918.065137 rgb/1305031918.065137.png 1305031918.081372 depth/1305031918.081372.png
1305031918.101060 rgb/1305031918.101060.png 1305031918.113495 depth/1305031918.113495.png
1305031918.133054 rgb/1305031918.133054.png 1305031918.145896 depth/1305031918.145896.png
1305031918.165017 rgb/1305031918.165017.png 1305031918.179489 depth/1305031918.179489.png
1305031918.201086 rgb/1305031918.201086.png 1305031918.214208 depth/1305031918.214208.png
1305031918.233042 rgb/1305031918.233042.png 1305031918.244974 depth/1305031918.244974.png
1305031918.265256 rgb/1305031918.265256.png 1305031918.280832 depth/1305031918.280832.png
1305031918.301124 rgb/1305031918.301124.png 1305031918.312487 depth/1305031918.312487.png
1305031918.333165 rgb/1305031918.333165.png 1305031918.344896 depth/1305031918.344896.png
1305031918.365072 rgb/1305031918.365072.png 1305031918.379884 depth/1305031918.379884.png
1305031918.401030 rgb/1305031918.401030.png 1305031918.413065 depth/1305031918.413065.png
1305031918.433043 rgb/1305031918.433043.png 1305031918.445292 depth/1305031918.445292.png
1305031918.465089 rgb/1305031918.465089.png 1305031918.481811 depth/1305031918.481811.png
1305031918.501125 rgb/1305031918.501125.png 1305031918.513488 depth/1305031918.513488.png
1305031918.533134 rgb/1305031918.533134.png 1305031918.545221 depth/1305031918.545221.png
1305031918.565018 rgb/1305031918.565018.png 1305031918.582328 depth/1305031918.582328.png
1305031918.601029 rgb/1305031918.601029.png 1305031918.613230 depth/1305031918.613230.png
1305031918.633027 rgb/1305031918.633027.png 1305031918.645169 depth/1305031918.645169.png
1305031918.665112 rgb/1305031918.665112.png 1305031918.681778 depth/1305031918.681778.png
1305031918.701017 rgb/1305031918.701017.png 1305031918.713496 depth/1305031918.713496.png
1305031918.765151 rgb/1305031918.765151.png 1305031918.749734 depth/1305031918.749734.png
1305031918.801097 rgb/1305031918.801097.png 1305031918.814538 depth/1305031918.814538.png
1305031918.833123 rgb/1305031918.833123.png 1305031918.850071 depth/1305031918.850071.png
1305031918.865115 rgb/1305031918.865115.png 1305031918.880096 depth/1305031918.880096.png
1305031918.901084 rgb/1305031918.901084.png 1305031918.912498 depth/1305031918.912498.png
1305031918.933071 rgb/1305031918.933071.png 1305031918.948107 depth/1305031918.948107.png
1305031918.965058 rgb/1305031918.965058.png 1305031918.980882 depth/1305031918.980882.png
1305031919.001053 rgb/1305031919.001053.png 1305031919.013079 depth/1305031919.013079.png
1305031919.033082 rgb/1305031919.033082.png 1305031919.047888 depth/1305031919.047888.png
1305031919.065147 rgb/1305031919.065147.png 1305031919.081202 depth/1305031919.081202.png
1305031919.101028 rgb/1305031919.101028.png 1305031919.113268 depth/1305031919.113268.png
1305031919.133133 rgb/1305031919.133133.png 1305031919.149786 depth/1305031919.149786.png
1305031919.165110 rgb/1305031919.165110.png 1305031919.180150 depth/1305031919.180150.png
1305031919.201124 rgb/1305031919.201124.png 1305031919.212613 depth/1305031919.212613.png
1305031919.233093 rgb/1305031919.233093.png 1305031919.248053 depth/1305031919.248053.png
1305031919.265125 rgb/1305031919.265125.png 1305031919.282212 depth/1305031919.282212.png
1305031919.301119 rgb/1305031919.301119.png 1305031919.313576 depth/1305031919.313576.png
1305031919.333120 rgb/1305031919.333120.png 1305031919.348352 depth/1305031919.348352.png
1305031919.364948 rgb/1305031919.364948.png 1305031919.376791 depth/1305031919.376791.png
1305031919.401124 rgb/1305031919.401124.png 1305031919.413966 depth/1305031919.413966.png
1305031919.433256 rgb/1305031919.433256.png 1305031919.446851 depth/1305031919.446851.png
1305031919.465070 rgb/1305031919.465070.png 1305031919.480223 depth/1305031919.480223.png
1305031919.501049 rgb/1305031919.501049.png 1305031919.512137 depth/1305031919.512137.png
1305031919.533110 rgb/1305031919.533110.png 1305031919.548061 depth/1305031919.548061.png
1305031919.565165 rgb/1305031919.565165.png 1305031919.580925 depth/1305031919.580925.png
1305031919.601094 rgb/1305031919.601094.png 1305031919.611928 depth/1305031919.611928.png
1305031919.633127 rgb/1305031919.633127.png 1305031919.649872 depth/1305031919.649872.png
1305031919.665042 rgb/1305031919.665042.png 1305031919.680144 depth/1305031919.680144.png
1305031919.701092 rgb/1305031919.701092.png 1305031919.711961 depth/1305031919.711961.png
1305031919.733117 rgb/1305031919.733117.png 1305031919.747809 depth/1305031919.747809.png
1305031919.765060 rgb/1305031919.765060.png 1305031919.779527 depth/1305031919.779527.png
1305031919.801129 rgb/1305031919.801129.png 1305031919.815366 depth/1305031919.815366.png
1305031919.833072 rgb/1305031919.833072.png 1305031919.849456 depth/1305031919.849456.png
1305031919.865180 rgb/1305031919.865180.png 1305031919.880464 depth/1305031919.880464.png
1305031919.901067 rgb/1305031919.901067.png 1305031919.917226 depth/1305031919.917226.png
1305031919.933102 rgb/1305031919.933102.png 1305031919.948072 depth/1305031919.948072.png
1305031919.965129 rgb/1305031919.965129.png 1305031919.981539 depth/1305031919.981539.png
1305031920.001054 rgb/1305031920.001054.png 1305031920.017137 depth/1305031920.017137.png
1305031920.033118 rgb/1305031920.033118.png 1305031920.048127 depth/1305031920.048127.png
1305031920.065136 rgb/1305031920.065136.png 1305031920.081263 depth/1305031920.081263.png
1305031920.101055 rgb/1305031920.101055.png 1305031920.116134 depth/1305031920.116134.png
1305031920.132987 rgb/1305031920.132987.png 1305031920.148679 depth/1305031920.148679.png
1305031920.165140 rgb/1305031920.165140.png 1305031920.180544 depth/1305031920.180544.png
1305031920.201166 rgb/1305031920.201166.png 1305031920.217426 depth/1305031920.217426.png
1305031920.233083 rgb/1305031920.233083.png 1305031920.248168 depth/1305031920.248168.png
1305031920.265120 rgb/1305031920.265120.png 1305031920.280534 depth/1305031920.280534.png
1305031920.301096 rgb/1305031920.301096.png 1305031920.316524 depth/1305031920.316524.png
1305031920.333124 rgb/1305031920.333124.png 1305031920.349842 depth/1305031920.349842.png
1305031920.365130 rgb/1305031920.365130.png 1305031920.380357 depth/1305031920.380357.png
1305031920.401115 rgb/1305031920.401115.png 1305031920.417274 depth/1305031920.417274.png
1305031920.433123 rgb/1305031920.433123.png 1305031920.448025 depth/1305031920.448025.png
1305031920.465148 rgb/1305031920.465148.png 1305031920.481785 depth/1305031920.481785.png
1305031920.501107 rgb/1305031920.501107.png 1305031920.517298 depth/1305031920.517298.png
1305031920.533105 rgb/1305031920.533105.png 1305031920.547964 depth/1305031920.547964.png
1305031920.565153 rgb/1305031920.565153.png 1305031920.581456 depth/1305031920.581456.png
1305031920.633105 rgb/1305031920.633105.png 1305031920.617995 depth/1305031920.617995.png
1305031920.665129 rgb/1305031920.665129.png 1305031920.680130 depth/1305031920.680130.png
1305031920.701147 rgb/1305031920.701147.png 1305031920.717318 depth/1305031920.717318.png
1305031920.733091 rgb/1305031920.733091.png 1305031920.747997 depth/1305031920.747997.png
1305031920.765152 rgb/1305031920.765152.png 1305031920.780346 depth/1305031920.780346.png
1305031920.801031 rgb/1305031920.801031.png 1305031920.813643 depth/1305031920.813643.png
1305031920.833132 rgb/1305031920.833132.png 1305031920.848339 depth/1305031920.848339.png
1305031920.865163 rgb/1305031920.865163.png 1305031920.879246 depth/1305031920.879246.png
1305031920.901037 rgb/1305031920.901037.png 1305031920.915238 depth/1305031920.915238.png
1305031920.933077 rgb/1305031920.933077.png 1305031920.947777 depth/1305031920.947777.png
1305031920.965217 rgb/1305031920.965217.png 1305031920.981269 depth/1305031920.981269.png
1305031921.001108 rgb/1305031921.001108.png 1305031921.015897 depth/1305031921.015897.png
1305031921.033111 rgb/1305031921.033111.png 1305031921.046752 depth/1305031921.046752.png
1305031921.065147 rgb/1305031921.065147.png 1305031921.081623 depth/1305031921.081623.png
1305031921.101105 rgb/1305031921.101105.png 1305031921.116426 depth/1305031921.116426.png
1305031921.133159 rgb/1305031921.133159.png 1305031921.147542 depth/1305031921.147542.png
1305031921.165116 rgb/1305031921.165116.png 1305031921.183591 depth/1305031921.183591.png
1305031921.201159 rgb/1305031921.201159.png 1305031921.216248 depth/1305031921.216248.png
1305031921.233189 rgb/1305031921.233189.png 1305031921.247511 depth/1305031921.247511.png
1305031921.265164 rgb/1305031921.265164.png 1305031921.283682 depth/1305031921.283682.png
1305031921.301188 rgb/1305031921.301188.png 1305031921.316687 depth/1305031921.316687.png
1305031921.333158 rgb/1305031921.333158.png 1305031921.348715 depth/1305031921.348715.png
1305031921.365112 rgb/1305031921.365112.png 1305031921.383334 depth/1305031921.383334.png
1305031921.401108 rgb/1305031921.401108.png 1305031921.417533 depth/1305031921.417533.png
1305031921.433143 rgb/1305031921.433143.png 1305031921.447829 depth/1305031921.447829.png
1305031921.465014 rgb/1305031921.465014.png 1305031921.483449 depth/1305031921.483449.png
1305031921.501096 rgb/1305031921.501096.png 1305031921.516337 depth/1305031921.516337.png
1305031921.533099 rgb/1305031921.533099.png 1305031921.547693 depth/1305031921.547693.png
1305031921.565119 rgb/1305031921.565119.png 1305031921.584755 depth/1305031921.584755.png
1305031921.601114 rgb/1305031921.601114.png 1305031921.616860 depth/1305031921.616860.png
1305031921.633107 rgb/1305031921.633107.png 1305031921.648077 depth/1305031921.648077.png
1305031921.701068 rgb/1305031921.701068.png 1305031921.684108 depth/1305031921.684108.png
1305031921.733068 rgb/1305031921.733068.png 1305031921.717161 depth/1305031921.717161.png
1305031921.765060 rgb/1305031921.765060.png 1305031921.749472 depth/1305031921.749472.png
1305031921.801034 rgb/1305031921.801034.png 1305031921.815490 depth/1305031921.815490.png
1305031921.833122 rgb/1305031921.833122.png 1305031921.847815 depth/1305031921.847815.png
1305031921.865148 rgb/1305031921.865148.png 1305031921.883647 depth/1305031921.883647.png
1305031921.901117 rgb/1305031921.901117.png 1305031921.915912 depth/1305031921.915912.png
1305031921.933132 rgb/1305031921.933132.png 1305031921.947748 depth/1305031921.947748.png
1305031921.965107 rgb/1305031921.965107.png 1305031921.983963 depth/1305031921.983963.png
1305031922.001101 rgb/1305031922.001101.png 1305031922.017509 depth/1305031922.017509.png
1305031922.033170 rgb/1305031922.033170.png 1305031922.048087 depth/1305031922.048087.png
1305031922.101032 rgb/1305031922.101032.png 1305031922.084015 depth/1305031922.084015.png
1305031922.133245 rgb/1305031922.133245.png 1305031922.117449 depth/1305031922.117449.png
1305031922.165062 rgb/1305031922.165062.png 1305031922.150410 depth/1305031922.150410.png
1305031922.201057 rgb/1305031922.201057.png 1305031922.217879 depth/1305031922.217879.png
1305031922.233248 rgb/1305031922.233248.png 1305031922.248353 depth/1305031922.248353.png
1305031922.265183 rgb/1305031922.265183.png 1305031922.284278 depth/1305031922.284278.png
1305031922.301137 rgb/1305031922.301137.png 1305031922.315988 depth/1305031922.315988.png
1305031922.333215 rgb/1305031922.333215.png 1305031922.348617 depth/1305031922.348617.png
1305031922.365143 rgb/1305031922.365143.png 1305031922.384534 depth/1305031922.384534.png
1305031922.401139 rgb/1305031922.401139.png 1305031922.414362 depth/1305031922.414362.png
1305031922.465219 rgb/1305031922.465219.png 1305031922.449565 depth/1305031922.449565.png
1305031922.501312 rgb/1305031922.501312.png 1305031922.483598 depth/1305031922.483598.png
1305031922.533139 rgb/1305031922.533139.png 1305031922.517313 depth/1305031922.517313.png
1305031922.565031 rgb/1305031922.565031.png 1305031922.551135 depth/1305031922.551135.png
1305031922.601111 rgb/1305031922.601111.png 1305031922.616826 depth/1305031922.616826.png
1305031922.665318 rgb/1305031922.665318.png 1305031922.651650 depth/1305031922.651650.png
1305031922.701355 rgb/1305031922.701355.png 1305031922.684543 depth/1305031922.684543.png
1305031922.733235 rgb/1305031922.733235.png 1305031922.718051 depth/1305031922.718051.png
1305031922.765373 rgb/1305031922.765373.png 1305031922.752032 depth/1305031922.752032.png
1305031922.801220 rgb/1305031922.801220.png 1305031922.784245 depth/1305031922.784245.png
1305031922.833262 rgb/1305031922.833262.png 1305031922.818079 depth/1305031922.818079.png
1305031922.865045 rgb/1305031922.865045.png 1305031922.851561 depth/1305031922.851561.png
1305031922.901109 rgb/1305031922.901109.png 1305031922.916045 depth/1305031922.916045.png
1305031922.965220 rgb/1305031922.965220.png 1305031922.951632 depth/1305031922.951632.png
1305031923.001054 rgb/1305031923.001054.png 1305031923.016127 depth/1305031923.016127.png
1305031923.065085 rgb/1305031923.065085.png 1305031923.051643 depth/1305031923.051643.png
1305031923.101056 rgb/1305031923.101056.png 1305031923.083189 depth/1305031923.083189.png
1305031923.133238 rgb/1305031923.133238.png 1305031923.117556 depth/1305031923.117556.png
1305031923.165168 rgb/1305031923.165168.png 1305031923.152033 depth/1305031923.152033.png
1305031923.201181 rgb/1305031923.201181.png 1305031923.215945 depth/1305031923.215945.png
1305031923.265159 rgb/1305031923.265159.png 1305031923.251678 depth/1305031923.251678.png
1305031923.301183 rgb/1305031923.301183.png 1305031923.283836 depth/1305031923.283836.png
1305031923.333169 rgb/1305031923.333169.png 1305031923.317750 depth/1305031923.317750.png
1305031923.365230 rgb/1305031923.365230.png 1305031923.351741 depth/1305031923.351741.png
1305031923.401139 rgb/1305031923.401139.png 1305031923.384405 depth/1305031923.384405.png
1305031923.433112 rgb/1305031923.433112.png 1305031923.417551 depth/1305031923.417551.png
1305031923.465290 rgb/1305031923.465290.png 1305031923.452014 depth/1305031923.452014.png
1305031923.501145 rgb/1305031923.501145.png 1305031923.483984 depth/1305031923.483984.png
1305031923.533199 rgb/1305031923.533199.png 1305031923.517826 depth/1305031923.517826.png
1305031923.565198 rgb/1305031923.565198.png 1305031923.551611 depth/1305031923.551611.png
1305031923.601069 rgb/1305031923.601069.png 1305031923.584004 depth/1305031923.584004.png
1305031923.633244 rgb/1305031923.633244.png 1305031923.617213 depth/1305031923.617213.png
1305031923.665141 rgb/1305031923.665141.png 1305031923.651604 depth/1305031923.651604.png
1305031923.701144 rgb/1305031923.701144.png 1305031923.683339 depth/1305031923.683339.png
1305031923.733145 rgb/1305031923.733145.png 1305031923.719218 depth/1305031923.719218.png
1305031923.765175 rgb/1305031923.765175.png 1305031923.751229 depth/1305031923.751229.png
1305031923.801150 rgb/1305031923.801150.png 1305031923.784138 depth/1305031923.784138.png
1305031923.833045 rgb/1305031923.833045.png 1305031923.819707 depth/1305031923.819707.png
1305031923.865161 rgb/1305031923.865161.png 1305031923.848797 depth/1305031923.848797.png
1305031923.901121 rgb/1305031923.901121.png 1305031923.883914 depth/1305031923.883914.png
1305031923.933140 rgb/1305031923.933140.png 1305031923.919849 depth/1305031923.919849.png
1305031923.965198 rgb/1305031923.965198.png 1305031923.952341 depth/1305031923.952341.png
1305031924.001096 rgb/1305031924.001096.png 1305031923.985402 depth/1305031923.985402.png
1305031924.033250 rgb/1305031924.033250.png 1305031924.020347 depth/1305031924.020347.png
1305031924.065224 rgb/1305031924.065224.png 1305031924.052305 depth/1305031924.052305.png
1305031924.101175 rgb/1305031924.101175.png 1305031924.084935 depth/1305031924.084935.png
1305031924.133285 rgb/1305031924.133285.png 1305031924.120309 depth/1305031924.120309.png
1305031924.165591 rgb/1305031924.165591.png 1305031924.149942 depth/1305031924.149942.png
1305031924.201130 rgb/1305031924.201130.png 1305031924.183240 depth/1305031924.183240.png
1305031924.233238 rgb/1305031924.233238.png 1305031924.221139 depth/1305031924.221139.png
1305031924.265335 rgb/1305031924.265335.png 1305031924.251933 depth/1305031924.251933.png
1305031924.301099 rgb/1305031924.301099.png 1305031924.284047 depth/1305031924.284047.png
1305031924.333113 rgb/1305031924.333113.png 1305031924.319056 depth/1305031924.319056.png
1305031924.365169 rgb/1305031924.365169.png 1305031924.351287 depth/1305031924.351287.png
1305031924.401095 rgb/1305031924.401095.png 1305031924.383380 depth/1305031924.383380.png
1305031924.433069 rgb/1305031924.433069.png 1305031924.419225 depth/1305031924.419225.png
1305031924.465394 rgb/1305031924.465394.png 1305031924.452792 depth/1305031924.452792.png
1305031924.501116 rgb/1305031924.501116.png 1305031924.483315 depth/1305031924.483315.png
1305031924.533245 rgb/1305031924.533245.png 1305031924.519657 depth/1305031924.519657.png
1305031924.565264 rgb/1305031924.565264.png 1305031924.552273 depth/1305031924.552273.png
1305031924.601161 rgb/1305031924.601161.png 1305031924.584109 depth/1305031924.584109.png
1305031924.633221 rgb/1305031924.633221.png 1305031924.620515 depth/1305031924.620515.png
1305031924.665187 rgb/1305031924.665187.png 1305031924.652060 depth/1305031924.652060.png
1305031924.701168 rgb/1305031924.701168.png 1305031924.684319 depth/1305031924.684319.png
1305031924.733166 rgb/1305031924.733166.png 1305031924.719995 depth/1305031924.719995.png
1305031924.765170 rgb/1305031924.765170.png 1305031924.751699 depth/1305031924.751699.png
1305031924.801057 rgb/1305031924.801057.png 1305031924.783411 depth/1305031924.783411.png
1305031924.833187 rgb/1305031924.833187.png 1305031924.819277 depth/1305031924.819277.png
1305031924.865165 rgb/1305031924.865165.png 1305031924.851149 depth/1305031924.851149.png
1305031924.901110 rgb/1305031924.901110.png 1305031924.887231 depth/1305031924.887231.png
1305031924.933186 rgb/1305031924.933186.png 1305031924.919219 depth/1305031924.919219.png
1305031924.969060 rgb/1305031924.969060.png 1305031924.951326 depth/1305031924.951326.png
1305031925.001103 rgb/1305031925.001103.png 1305031924.987062 depth/1305031924.987062.png
1305031925.033148 rgb/1305031925.033148.png 1305031925.019418 depth/1305031925.019418.png
1305031925.069090 rgb/1305031925.069090.png 1305031925.051227 depth/1305031925.051227.png
1305031925.101107 rgb/1305031925.101107.png 1305031925.086881 depth/1305031925.086881.png
1305031925.133209 rgb/1305031925.133209.png 1305031925.119070 depth/1305031925.119070.png
1305031925.169080 rgb/1305031925.169080.png 1305031925.150861 depth/1305031925.150861.png
1305031925.201117 rgb/1305031925.201117.png 1305031925.186995 depth/1305031925.186995.png
1305031925.233193 rgb/1305031925.233193.png 1305031925.219143 depth/1305031925.219143.png
1305031925.269164 rgb/1305031925.269164.png 1305031925.250215 depth/1305031925.250215.png
1305031925.301283 rgb/1305031925.301283.png 1305031925.287610 depth/1305031925.287610.png
1305031925.333142 rgb/1305031925.333142.png 1305031925.318360 depth/1305031925.318360.png
1305031925.369107 rgb/1305031925.369107.png 1305031925.351623 depth/1305031925.351623.png
1305031925.401456 rgb/1305031925.401456.png 1305031925.386446 depth/1305031925.386446.png
1305031925.433406 rgb/1305031925.433406.png 1305031925.420497 depth/1305031925.420497.png
1305031925.469099 rgb/1305031925.469099.png 1305031925.451669 depth/1305031925.451669.png
1305031925.501267 rgb/1305031925.501267.png 1305031925.487976 depth/1305031925.487976.png
1305031925.533321 rgb/1305031925.533321.png 1305031925.520197 depth/1305031925.520197.png
1305031925.569132 rgb/1305031925.569132.png 1305031925.551723 depth/1305031925.551723.png
1305031925.601218 rgb/1305031925.601218.png 1305031925.587951 depth/1305031925.587951.png
1305031925.633430 rgb/1305031925.633430.png 1305031925.620389 depth/1305031925.620389.png
1305031925.669137 rgb/1305031925.669137.png 1305031925.652177 depth/1305031925.652177.png
1305031925.701322 rgb/1305031925.701322.png 1305031925.688138 depth/1305031925.688138.png
1305031925.733167 rgb/1305031925.733167.png 1305031925.719963 depth/1305031925.719963.png
1305031925.769246 rgb/1305031925.769246.png 1305031925.752010 depth/1305031925.752010.png
1305031925.801208 rgb/1305031925.801208.png 1305031925.788128 depth/1305031925.788128.png
1305031925.833148 rgb/1305031925.833148.png 1305031925.819737 depth/1305031925.819737.png
1305031925.869197 rgb/1305031925.869197.png 1305031925.852900 depth/1305031925.852900.png
1305031925.901176 rgb/1305031925.901176.png 1305031925.887783 depth/1305031925.887783.png
1305031925.933170 rgb/1305031925.933170.png 1305031925.917070 depth/1305031925.917070.png
1305031925.969198 rgb/1305031925.969198.png 1305031925.952071 depth/1305031925.952071.png
1305031926.001186 rgb/1305031926.001186.png 1305031925.987927 depth/1305031925.987927.png
1305031926.033156 rgb/1305031926.033156.png 1305031926.019599 depth/1305031926.019599.png
1305031926.069077 rgb/1305031926.069077.png 1305031926.051425 depth/1305031926.051425.png
1305031926.101106 rgb/1305031926.101106.png 1305031926.087671 depth/1305031926.087671.png
1305031926.133181 rgb/1305031926.133181.png 1305031926.119488 depth/1305031926.119488.png
1305031926.169101 rgb/1305031926.169101.png 1305031926.155476 depth/1305031926.155476.png
1305031926.201141 rgb/1305031926.201141.png 1305031926.187287 depth/1305031926.187287.png
1305031926.233134 rgb/1305031926.233134.png 1305031926.219471 depth/1305031926.219471.png
1305031926.269135 rgb/1305031926.269135.png 1305031926.255515 depth/1305031926.255515.png
1305031926.301054 rgb/1305031926.301054.png 1305031926.287524 depth/1305031926.287524.png
1305031926.333164 rgb/1305031926.333164.png 1305031926.319314 depth/1305031926.319314.png
1305031926.369064 rgb/1305031926.369064.png 1305031926.355226 depth/1305031926.355226.png
1305031926.401166 rgb/1305031926.401166.png 1305031926.387186 depth/1305031926.387186.png
1305031926.433155 rgb/1305031926.433155.png 1305031926.416195 depth/1305031926.416195.png
1305031926.469090 rgb/1305031926.469090.png 1305031926.456138 depth/1305031926.456138.png
1305031926.501075 rgb/1305031926.501075.png 1305031926.487337 depth/1305031926.487337.png
1305031926.533176 rgb/1305031926.533176.png 1305031926.519488 depth/1305031926.519488.png
1305031926.569122 rgb/1305031926.569122.png 1305031926.555508 depth/1305031926.555508.png
1305031926.601166 rgb/1305031926.601166.png 1305031926.587389 depth/1305031926.587389.png
1305031926.633127 rgb/1305031926.633127.png 1305031926.617031 depth/1305031926.617031.png
1305031926.669140 rgb/1305031926.669140.png 1305031926.655592 depth/1305031926.655592.png
1305031926.701042 rgb/1305031926.701042.png 1305031926.686940 depth/1305031926.686940.png
1305031926.733207 rgb/1305031926.733207.png 1305031926.716774 depth/1305031926.716774.png
1305031926.769141 rgb/1305031926.769141.png 1305031926.754636 depth/1305031926.754636.png
1305031926.801342 rgb/1305031926.801342.png 1305031926.787267 depth/1305031926.787267.png
1305031926.833209 rgb/1305031926.833209.png 1305031926.817567 depth/1305031926.817567.png
1305031926.869333 rgb/1305031926.869333.png 1305031926.856453 depth/1305031926.856453.png
1305031926.901097 rgb/1305031926.901097.png 1305031926.885854 depth/1305031926.885854.png
1305031926.933348 rgb/1305031926.933348.png 1305031926.920915 depth/1305031926.920915.png
1305031926.969122 rgb/1305031926.969122.png 1305031926.956342 depth/1305031926.956342.png
1305031927.001575 rgb/1305031927.001575.png 1305031926.988250 depth/1305031926.988250.png
1305031927.033929 rgb/1305031927.033929.png 1305031927.021193 depth/1305031927.021193.png
1305031927.070528 rgb/1305031927.070528.png 1305031927.056355 depth/1305031927.056355.png
1305031927.101272 rgb/1305031927.101272.png 1305031927.088782 depth/1305031927.088782.png
1305031927.133471 rgb/1305031927.133471.png 1305031927.120454 depth/1305031927.120454.png
1305031927.169161 rgb/1305031927.169161.png 1305031927.156388 depth/1305031927.156388.png
1305031927.201210 rgb/1305031927.201210.png 1305031927.188222 depth/1305031927.188222.png
1305031927.233491 rgb/1305031927.233491.png 1305031927.220398 depth/1305031927.220398.png
1305031927.269153 rgb/1305031927.269153.png 1305031927.255554 depth/1305031927.255554.png
1305031927.301135 rgb/1305031927.301135.png 1305031927.288179 depth/1305031927.288179.png
1305031927.333139 rgb/1305031927.333139.png 1305031927.319728 depth/1305031927.319728.png
1305031927.369147 rgb/1305031927.369147.png 1305031927.355704 depth/1305031927.355704.png
1305031927.401161 rgb/1305031927.401161.png 1305031927.387697 depth/1305031927.387697.png
1305031927.433274 rgb/1305031927.433274.png 1305031927.423646 depth/1305031927.423646.png
1305031927.469105 rgb/1305031927.469105.png 1305031927.455842 depth/1305031927.455842.png
1305031927.501136 rgb/1305031927.501136.png 1305031927.487526 depth/1305031927.487526.png
1305031927.533182 rgb/1305031927.533182.png 1305031927.523735 depth/1305031927.523735.png
1305031927.569225 rgb/1305031927.569225.png 1305031927.555610 depth/1305031927.555610.png
1305031927.601132 rgb/1305031927.601132.png 1305031927.587778 depth/1305031927.587778.png
1305031927.633201 rgb/1305031927.633201.png 1305031927.623566 depth/1305031927.623566.png
1305031927.669158 rgb/1305031927.669158.png 1305031927.655615 depth/1305031927.655615.png
1305031927.701131 rgb/1305031927.701131.png 1305031927.687849 depth/1305031927.687849.png
1305031927.733219 rgb/1305031927.733219.png 1305031927.720304 depth/1305031927.720304.png
1305031927.769158 rgb/1305031927.769158.png 1305031927.755615 depth/1305031927.755615.png
1305031927.801109 rgb/1305031927.801109.png 1305031927.784053 depth/1305031927.784053.png
1305031927.833282 rgb/1305031927.833282.png 1305031927.825135 depth/1305031927.825135.png
1305031927.869143 rgb/1305031927.869143.png 1305031927.855551 depth/1305031927.855551.png
1305031927.901130 rgb/1305031927.901130.png 1305031927.887591 depth/1305031927.887591.png
1305031927.933465 rgb/1305031927.933465.png 1305031927.923620 depth/1305031927.923620.png
1305031927.969176 rgb/1305031927.969176.png 1305031927.955459 depth/1305031927.955459.png
1305031928.001134 rgb/1305031928.001134.png 1305031927.987655 depth/1305031927.987655.png
1305031928.033186 rgb/1305031928.033186.png 1305031928.023669 depth/1305031928.023669.png
1305031928.069125 rgb/1305031928.069125.png 1305031928.055649 depth/1305031928.055649.png
1305031928.101114 rgb/1305031928.101114.png 1305031928.087657 depth/1305031928.087657.png
1305031928.133202 rgb/1305031928.133202.png 1305031928.123611 depth/1305031928.123611.png
1305031928.169018 rgb/1305031928.169018.png 1305031928.153645 depth/1305031928.153645.png
1305031928.201096 rgb/1305031928.201096.png 1305031928.185349 depth/1305031928.185349.png
1305031928.233133 rgb/1305031928.233133.png 1305031928.223567 depth/1305031928.223567.png
1305031928.269216 rgb/1305031928.269216.png 1305031928.256019 depth/1305031928.256019.png
1305031928.301255 rgb/1305031928.301255.png 1305031928.287847 depth/1305031928.287847.png
1305031928.333609 rgb/1305031928.333609.png 1305031928.324414 depth/1305031928.324414.png
1305031928.369520 rgb/1305031928.369520.png 1305031928.356445 depth/1305031928.356445.png
1305031928.401116 rgb/1305031928.401116.png 1305031928.388295 depth/1305031928.388295.png
1305031928.433543 rgb/1305031928.433543.png 1305031928.424766 depth/1305031928.424766.png
1305031928.469232 rgb/1305031928.469232.png 1305031928.456406 depth/1305031928.456406.png
1305031928.501428 rgb/1305031928.501428.png 1305031928.489516 depth/1305031928.489516.png
1305031928.533982 rgb/1305031928.533982.png 1305031928.524415 depth/1305031928.524415.png
1305031928.569299 rgb/1305031928.569299.png 1305031928.556287 depth/1305031928.556287.png
1305031928.601271 rgb/1305031928.601271.png 1305031928.588557 depth/1305031928.588557.png
1305031928.633595 rgb/1305031928.633595.png 1305031928.624251 depth/1305031928.624251.png
1305031928.669146 rgb/1305031928.669146.png 1305031928.656233 depth/1305031928.656233.png
1305031928.701110 rgb/1305031928.701110.png 1305031928.691555 depth/1305031928.691555.png
1305031928.733185 rgb/1305031928.733185.png 1305031928.723927 depth/1305031928.723927.png
1305031928.769202 rgb/1305031928.769202.png 1305031928.755499 depth/1305031928.755499.png
1305031928.801117 rgb/1305031928.801117.png 1305031928.791463 depth/1305031928.791463.png
1305031928.833193 rgb/1305031928.833193.png 1305031928.823577 depth/1305031928.823577.png
1305031928.869148 rgb/1305031928.869148.png 1305031928.855468 depth/1305031928.855468.png
1305031928.901197 rgb/1305031928.901197.png 1305031928.891499 depth/1305031928.891499.png
1305031928.933215 rgb/1305031928.933215.png 1305031928.923473 depth/1305031928.923473.png
1305031928.969097 rgb/1305031928.969097.png 1305031928.955544 depth/1305031928.955544.png
1305031929.001155 rgb/1305031929.001155.png 1305031928.991477 depth/1305031928.991477.png
1305031929.033640 rgb/1305031929.033640.png 1305031929.023472 depth/1305031929.023472.png
1305031929.069089 rgb/1305031929.069089.png 1305031929.052047 depth/1305031929.052047.png
1305031929.101213 rgb/1305031929.101213.png 1305031929.091469 depth/1305031929.091469.png
1305031929.133202 rgb/1305031929.133202.png 1305031929.123397 depth/1305031929.123397.png
1305031929.169204 rgb/1305031929.169204.png 1305031929.155442 depth/1305031929.155442.png
1305031929.201163 rgb/1305031929.201163.png 1305031929.191433 depth/1305031929.191433.png
1305031929.233293 rgb/1305031929.233293.png 1305031929.224389 depth/1305031929.224389.png
1305031929.269214 rgb/1305031929.269214.png 1305031929.256040 depth/1305031929.256040.png
1305031929.301292 rgb/1305031929.301292.png 1305031929.292331 depth/1305031929.292331.png
1305031929.333529 rgb/1305031929.333529.png 1305031929.324071 depth/1305031929.324071.png
1305031929.369189 rgb/1305031929.369189.png 1305031929.356012 depth/1305031929.356012.png
1305031929.401369 rgb/1305031929.401369.png 1305031929.391503 depth/1305031929.391503.png
1305031929.433239 rgb/1305031929.433239.png 1305031929.423543 depth/1305031929.423543.png
1305031929.469219 rgb/1305031929.469219.png 1305031929.455568 depth/1305031929.455568.png
1305031929.501198 rgb/1305031929.501198.png 1305031929.491502 depth/1305031929.491502.png
1305031929.533262 rgb/1305031929.533262.png 1305031929.523520 depth/1305031929.523520.png
1305031929.569172 rgb/1305031929.569172.png 1305031929.555525 depth/1305031929.555525.png
1305031929.601101 rgb/1305031929.601101.png 1305031929.591341 depth/1305031929.591341.png
1305031929.634447 rgb/1305031929.634447.png 1305031929.627102 depth/1305031929.627102.png
1305031929.669287 rgb/1305031929.669287.png 1305031929.652934 depth/1305031929.652934.png
1305031929.701269 rgb/1305031929.701269.png 1305031929.688977 depth/1305031929.688977.png
1305031929.733617 rgb/1305031929.733617.png 1305031929.722904 depth/1305031929.722904.png
1305031929.769190 rgb/1305031929.769190.png 1305031929.755544 depth/1305031929.755544.png
1305031929.801229 rgb/1305031929.801229.png 1305031929.791661 depth/1305031929.791661.png
1305031929.833358 rgb/1305031929.833358.png 1305031929.824100 depth/1305031929.824100.png
1305031929.869242 rgb/1305031929.869242.png 1305031929.859997 depth/1305031929.859997.png
1305031929.901292 rgb/1305031929.901292.png 1305031929.892100 depth/1305031929.892100.png
1305031929.933176 rgb/1305031929.933176.png 1305031929.920589 depth/1305031929.920589.png
1305031929.969176 rgb/1305031929.969176.png 1305031929.960336 depth/1305031929.960336.png
1305031930.001350 rgb/1305031930.001350.png 1305031929.992281 depth/1305031929.992281.png
1305031930.033650 rgb/1305031930.033650.png 1305031930.024129 depth/1305031930.024129.png
1305031930.069293 rgb/1305031930.069293.png 1305031930.059766 depth/1305031930.059766.png
1305031930.101133 rgb/1305031930.101133.png 1305031930.088504 depth/1305031930.088504.png
1305031930.134163 rgb/1305031930.134163.png 1305031930.122266 depth/1305031930.122266.png
1305031930.169117 rgb/1305031930.169117.png 1305031930.159452 depth/1305031930.159452.png
1305031930.201148 rgb/1305031930.201148.png 1305031930.191333 depth/1305031930.191333.png
1305031930.233355 rgb/1305031930.233355.png 1305031930.223366 depth/1305031930.223366.png
1305031930.269064 rgb/1305031930.269064.png 1305031930.259685 depth/1305031930.259685.png
1305031930.301105 rgb/1305031930.301105.png 1305031930.291415 depth/1305031930.291415.png
1305031930.333138 rgb/1305031930.333138.png 1305031930.324425 depth/1305031930.324425.png
1305031930.369794 rgb/1305031930.369794.png 1305031930.360687 depth/1305031930.360687.png
1305031930.401077 rgb/1305031930.401077.png 1305031930.392204 depth/1305031930.392204.png
1305031930.433290 rgb/1305031930.433290.png 1305031930.424494 depth/1305031930.424494.png
1305031930.469130 rgb/1305031930.469130.png 1305031930.460645 depth/1305031930.460645.png
1305031930.501044 rgb/1305031930.501044.png 1305031930.491893 depth/1305031930.491893.png
1305031930.533067 rgb/1305031930.533067.png 1305031930.523304 depth/1305031930.523304.png
1305031930.569007 rgb/1305031930.569007.png 1305031930.559268 depth/1305031930.559268.png
1305031930.601041 rgb/1305031930.601041.png 1305031930.591038 depth/1305031930.591038.png
1305031930.633126 rgb/1305031930.633126.png 1305031930.620257 depth/1305031930.620257.png
1305031930.668925 rgb/1305031930.668925.png 1305031930.659428 depth/1305031930.659428.png
1305031930.701009 rgb/1305031930.701009.png 1305031930.691306 depth/1305031930.691306.png
1305031930.733195 rgb/1305031930.733195.png 1305031930.723254 depth/1305031930.723254.png
1305031930.769068 rgb/1305031930.769068.png 1305031930.759257 depth/1305031930.759257.png
1305031930.801055 rgb/1305031930.801055.png 1305031930.791524 depth/1305031930.791524.png
1305031930.833091 rgb/1305031930.833091.png 1305031930.823348 depth/1305031930.823348.png
1305031930.869070 rgb/1305031930.869070.png 1305031930.860005 depth/1305031930.860005.png
1305031930.900829 rgb/1305031930.900829.png 1305031930.887927 depth/1305031930.887927.png
1305031930.933330 rgb/1305031930.933330.png 1305031930.923290 depth/1305031930.923290.png
1305031930.969059 rgb/1305031930.969059.png 1305031930.959881 depth/1305031930.959881.png
1305031931.000795 rgb/1305031931.000795.png 1305031930.991760 depth/1305031930.991760.png
1305031931.033023 rgb/1305031931.033023.png 1305031931.023642 depth/1305031931.023642.png
1305031931.068905 rgb/1305031931.068905.png 1305031931.059938 depth/1305031931.059938.png
1305031931.100819 rgb/1305031931.100819.png 1305031931.091660 depth/1305031931.091660.png
1305031931.133042 rgb/1305031931.133042.png 1305031931.126327 depth/1305031931.126327.png
1305031931.168900 rgb/1305031931.168900.png 1305031931.156194 depth/1305031931.156194.png
1305031931.200696 rgb/1305031931.200696.png 1305031931.187879 depth/1305031931.187879.png
1305031931.233053 rgb/1305031931.233053.png 1305031931.226834 depth/1305031931.226834.png
1305031931.268951 rgb/1305031931.268951.png 1305031931.259538 depth/1305031931.259538.png
1305031931.300955 rgb/1305031931.300955.png 1305031931.291735 depth/1305031931.291735.png
1305031931.332991 rgb/1305031931.332991.png 1305031931.327534 depth/1305031931.327534.png
1305031931.369797 rgb/1305031931.369797.png 1305031931.359406 depth/1305031931.359406.png
1305031931.401337 rgb/1305031931.401337.png 1305031931.391729 depth/1305031931.391729.png
1305031931.432892 rgb/1305031931.432892.png 1305031931.427416 depth/1305031931.427416.png
1305031931.469079 rgb/1305031931.469079.png 1305031931.459719 depth/1305031931.459719.png
1305031931.500852 rgb/1305031931.500852.png 1305031931.491781 depth/1305031931.491781.png
1305031931.532871 rgb/1305031931.532871.png 1305031931.527311 depth/1305031931.527311.png
1305031931.569726 rgb/1305031931.569726.png 1305031931.559707 depth/1305031931.559707.png
1305031931.601199 rgb/1305031931.601199.png 1305031931.590720 depth/1305031931.590720.png
1305031931.633004 rgb/1305031931.633004.png 1305031931.627134 depth/1305031931.627134.png
1305031931.669064 rgb/1305031931.669064.png 1305031931.659798 depth/1305031931.659798.png
1305031931.701060 rgb/1305031931.701060.png 1305031931.691463 depth/1305031931.691463.png
1305031931.732985 rgb/1305031931.732985.png 1305031931.727210 depth/1305031931.727210.png
1305031931.768911 rgb/1305031931.768911.png 1305031931.759394 depth/1305031931.759394.png
1305031931.800959 rgb/1305031931.800959.png 1305031931.791463 depth/1305031931.791463.png
1305031931.832926 rgb/1305031931.832926.png 1305031931.827415 depth/1305031931.827415.png
1305031931.868988 rgb/1305031931.868988.png 1305031931.859949 depth/1305031931.859949.png
1305031931.900957 rgb/1305031931.900957.png 1305031931.891964 depth/1305031931.891964.png
1305031931.932907 rgb/1305031931.932907.png 1305031931.927455 depth/1305031931.927455.png
1305031931.968902 rgb/1305031931.968902.png 1305031931.959755 depth/1305031931.959755.png
1305031932.000829 rgb/1305031932.000829.png 1305031931.991729 depth/1305031931.991729.png
1305031932.032913 rgb/1305031932.032913.png 1305031932.026867 depth/1305031932.026867.png
1305031932.068920 rgb/1305031932.068920.png 1305031932.058924 depth/1305031932.058924.png
1305031932.101294 rgb/1305031932.101294.png 1305031932.092565 depth/1305031932.092565.png
1305031932.132895 rgb/1305031932.132895.png 1305031932.127607 depth/1305031932.127607.png
1305031932.169077 rgb/1305031932.169077.png 1305031932.159854 depth/1305031932.159854.png
1305031932.200948 rgb/1305031932.200948.png 1305031932.192165 depth/1305031932.192165.png
1305031932.232821 rgb/1305031932.232821.png 1305031932.227671 depth/1305031932.227671.png
1305031932.268818 rgb/1305031932.268818.png 1305031932.259182 depth/1305031932.259182.png
1305031932.300945 rgb/1305031932.300945.png 1305031932.291317 depth/1305031932.291317.png
1305031932.333175 rgb/1305031932.333175.png 1305031932.326984 depth/1305031932.326984.png
1305031932.368837 rgb/1305031932.368837.png 1305031932.359352 depth/1305031932.359352.png
1305031932.401680 rgb/1305031932.401680.png 1305031932.395192 depth/1305031932.395192.png
1305031932.432994 rgb/1305031932.432994.png 1305031932.427402 depth/1305031932.427402.png
1305031932.469022 rgb/1305031932.469022.png 1305031932.460162 depth/1305031932.460162.png
1305031932.500893 rgb/1305031932.500893.png 1305031932.495912 depth/1305031932.495912.png
1305031932.532959 rgb/1305031932.532959.png 1305031932.527699 depth/1305031932.527699.png
1305031932.568972 rgb/1305031932.568972.png 1305031932.556042 depth/1305031932.556042.png
1305031932.600957 rgb/1305031932.600957.png 1305031932.593841 depth/1305031932.593841.png
1305031932.632929 rgb/1305031932.632929.png 1305031932.627666 depth/1305031932.627666.png
1305031932.669236 rgb/1305031932.669236.png 1305031932.659769 depth/1305031932.659769.png
1305031932.700806 rgb/1305031932.700806.png 1305031932.695841 depth/1305031932.695841.png
1305031932.732848 rgb/1305031932.732848.png 1305031932.727524 depth/1305031932.727524.png
1305031932.768757 rgb/1305031932.768757.png 1305031932.759892 depth/1305031932.759892.png
1305031932.800821 rgb/1305031932.800821.png 1305031932.795486 depth/1305031932.795486.png
1305031932.832891 rgb/1305031932.832891.png 1305031932.827627 depth/1305031932.827627.png
1305031932.869016 rgb/1305031932.869016.png 1305031932.859777 depth/1305031932.859777.png
1305031932.901214 rgb/1305031932.901214.png 1305031932.896209 depth/1305031932.896209.png
1305031932.932932 rgb/1305031932.932932.png 1305031932.928147 depth/1305031932.928147.png
1305031932.968787 rgb/1305031932.968787.png 1305031932.959759 depth/1305031932.959759.png
1305031933.001958 rgb/1305031933.001958.png 1305031932.995065 depth/1305031932.995065.png
1305031933.033045 rgb/1305031933.033045.png 1305031933.026975 depth/1305031933.026975.png
1305031933.068879 rgb/1305031933.068879.png 1305031933.059632 depth/1305031933.059632.png
1305031933.100908 rgb/1305031933.100908.png 1305031933.095661 depth/1305031933.095661.png
1305031933.132911 rgb/1305031933.132911.png 1305031933.127608 depth/1305031933.127608.png
1305031933.169450 rgb/1305031933.169450.png 1305031933.159744 depth/1305031933.159744.png
1305031933.200949 rgb/1305031933.200949.png 1305031933.195887 depth/1305031933.195887.png
1305031933.233374 rgb/1305031933.233374.png 1305031933.227642 depth/1305031933.227642.png
1305031933.269079 rgb/1305031933.269079.png 1305031933.259844 depth/1305031933.259844.png
1305031933.300869 rgb/1305031933.300869.png 1305031933.296061 depth/1305031933.296061.png
1305031933.332881 rgb/1305031933.332881.png 1305031933.327953 depth/1305031933.327953.png
1305031933.368978 rgb/1305031933.368978.png 1305031933.359852 depth/1305031933.359852.png
1305031933.400926 rgb/1305031933.400926.png 1305031933.395603 depth/1305031933.395603.png
1305031933.432912 rgb/1305031933.432912.png 1305031933.427651 depth/1305031933.427651.png
1305031933.469486 rgb/1305031933.469486.png 1305031933.459920 depth/1305031933.459920.png
1305031933.500809 rgb/1305031933.500809.png 1305031933.495920 depth/1305031933.495920.png
1305031933.533065 rgb/1305031933.533065.png 1305031933.527835 depth/1305031933.527835.png
1305031933.568861 rgb/1305031933.568861.png 1305031933.564265 depth/1305031933.564265.png
1305031933.600899 rgb/1305031933.600899.png 1305031933.595687 depth/1305031933.595687.png
1305031933.632949 rgb/1305031933.632949.png 1305031933.626979 depth/1305031933.626979.png
1305031933.669114 rgb/1305031933.669114.png 1305031933.663105 depth/1305031933.663105.png
1305031933.700931 rgb/1305031933.700931.png 1305031933.695772 depth/1305031933.695772.png
1305031933.732901 rgb/1305031933.732901.png 1305031933.727622 depth/1305031933.727622.png
1305031933.768934 rgb/1305031933.768934.png 1305031933.763831 depth/1305031933.763831.png
1305031933.800879 rgb/1305031933.800879.png 1305031933.795823 depth/1305031933.795823.png
1305031933.833132 rgb/1305031933.833132.png 1305031933.827513 depth/1305031933.827513.png
1305031933.868855 rgb/1305031933.868855.png 1305031933.863871 depth/1305031933.863871.png
1305031933.900942 rgb/1305031933.900942.png 1305031933.895826 depth/1305031933.895826.png
1305031933.932925 rgb/1305031933.932925.png 1305031933.927864 depth/1305031933.927864.png
1305031933.968843 rgb/1305031933.968843.png 1305031933.964067 depth/1305031933.964067.png
1305031934.000841 rgb/1305031934.000841.png 1305031933.996159 depth/1305031933.996159.png
1305031934.033000 rgb/1305031934.033000.png 1305031934.025036 depth/1305031934.025036.png
1305031934.068946 rgb/1305031934.068946.png 1305031934.062070 depth/1305031934.062070.png
1305031934.100917 rgb/1305031934.100917.png 1305031934.095754 depth/1305031934.095754.png
1305031934.132845 rgb/1305031934.132845.png 1305031934.123903 depth/1305031934.123903.png
1305031934.169177 rgb/1305031934.169177.png 1305031934.163843 depth/1305031934.163843.png
1305031934.200808 rgb/1305031934.200808.png 1305031934.196078 depth/1305031934.196078.png
1305031934.232870 rgb/1305031934.232870.png 1305031934.226959 depth/1305031934.226959.png
1305031934.269296 rgb/1305031934.269296.png 1305031934.263347 depth/1305031934.263347.png
1305031934.300934 rgb/1305031934.300934.png 1305031934.295644 depth/1305031934.295644.png
1305031934.336871 rgb/1305031934.336871.png 1305031934.327544 depth/1305031934.327544.png
1305031934.368906 rgb/1305031934.368906.png 1305031934.363432 depth/1305031934.363432.png
1305031934.400928 rgb/1305031934.400928.png 1305031934.395278 depth/1305031934.395278.png
1305031934.436865 rgb/1305031934.436865.png 1305031934.427107 depth/1305031934.427107.png
1305031934.469287 rgb/1305031934.469287.png 1305031934.460046 depth/1305031934.460046.png
1305031934.501241 rgb/1305031934.501241.png 1305031934.495228 depth/1305031934.495228.png
1305031934.536876 rgb/1305031934.536876.png 1305031934.527409 depth/1305031934.527409.png
1305031934.569101 rgb/1305031934.569101.png 1305031934.563395 depth/1305031934.563395.png
1305031934.600850 rgb/1305031934.600850.png 1305031934.595082 depth/1305031934.595082.png
1305031934.637030 rgb/1305031934.637030.png 1305031934.627102 depth/1305031934.627102.png
1305031934.668984 rgb/1305031934.668984.png 1305031934.662910 depth/1305031934.662910.png
1305031934.700945 rgb/1305031934.700945.png 1305031934.694817 depth/1305031934.694817.png
1305031934.736903 rgb/1305031934.736903.png 1305031934.726749 depth/1305031934.726749.png
1305031934.769124 rgb/1305031934.769124.png 1305031934.762903 depth/1305031934.762903.png
1305031934.801627 rgb/1305031934.801627.png 1305031934.794831 depth/1305031934.794831.png
1305031934.836769 rgb/1305031934.836769.png 1305031934.830983 depth/1305031934.830983.png
1305031934.869115 rgb/1305031934.869115.png 1305031934.862668 depth/1305031934.862668.png
1305031934.901010 rgb/1305031934.901010.png 1305031934.894445 depth/1305031934.894445.png
1305031934.937234 rgb/1305031934.937234.png 1305031934.931747 depth/1305031934.931747.png
1305031934.969077 rgb/1305031934.969077.png 1305031934.963384 depth/1305031934.963384.png
1305031935.001270 rgb/1305031935.001270.png 1305031934.995132 depth/1305031934.995132.png
1305031935.036852 rgb/1305031935.036852.png 1305031935.033022 depth/1305031935.033022.png
1305031935.069722 rgb/1305031935.069722.png 1305031935.063116 depth/1305031935.063116.png
1305031935.100912 rgb/1305031935.100912.png 1305031935.095058 depth/1305031935.095058.png
1305031935.136853 rgb/1305031935.136853.png 1305031935.130727 depth/1305031935.130727.png
1305031935.169281 rgb/1305031935.169281.png 1305031935.162214 depth/1305031935.162214.png
1305031935.200951 rgb/1305031935.200951.png 1305031935.194899 depth/1305031935.194899.png
1305031935.237095 rgb/1305031935.237095.png 1305031935.231025 depth/1305031935.231025.png
1305031935.268965 rgb/1305031935.268965.png 1305031935.260736 depth/1305031935.260736.png
1305031935.300805 rgb/1305031935.300805.png 1305031935.295152 depth/1305031935.295152.png
1305031935.336810 rgb/1305031935.336810.png 1305031935.330960 depth/1305031935.330960.png
1305031935.368827 rgb/1305031935.368827.png 1305031935.363255 depth/1305031935.363255.png
1305031935.400848 rgb/1305031935.400848.png 1305031935.394932 depth/1305031935.394932.png
1305031935.436887 rgb/1305031935.436887.png 1305031935.430905 depth/1305031935.430905.png
1305031935.468890 rgb/1305031935.468890.png 1305031935.463017 depth/1305031935.463017.png
1305031935.500863 rgb/1305031935.500863.png 1305031935.493044 depth/1305031935.493044.png
1305031935.536900 rgb/1305031935.536900.png 1305031935.530045 depth/1305031935.530045.png
1305031935.568783 rgb/1305031935.568783.png 1305031935.562732 depth/1305031935.562732.png
1305031935.600963 rgb/1305031935.600963.png 1305031935.594819 depth/1305031935.594819.png
1305031935.636916 rgb/1305031935.636916.png 1305031935.631390 depth/1305031935.631390.png
1305031935.669100 rgb/1305031935.669100.png 1305031935.663543 depth/1305031935.663543.png
1305031935.700948 rgb/1305031935.700948.png 1305031935.695531 depth/1305031935.695531.png
1305031935.736900 rgb/1305031935.736900.png 1305031935.731180 depth/1305031935.731180.png
1305031935.768974 rgb/1305031935.768974.png 1305031935.763521 depth/1305031935.763521.png
1305031935.801178 rgb/1305031935.801178.png 1305031935.795359 depth/1305031935.795359.png
1305031935.836877 rgb/1305031935.836877.png 1305031935.831205 depth/1305031935.831205.png
1305031935.869025 rgb/1305031935.869025.png 1305031935.863651 depth/1305031935.863651.png
1305031935.901144 rgb/1305031935.901144.png 1305031935.895325 depth/1305031935.895325.png
1305031935.936825 rgb/1305031935.936825.png 1305031935.931428 depth/1305031935.931428.png
1305031935.969109 rgb/1305031935.969109.png 1305031935.963243 depth/1305031935.963243.png
1305031936.000820 rgb/1305031936.000820.png 1305031935.995756 depth/1305031935.995756.png
1305031936.036965 rgb/1305031936.036965.png 1305031936.031927 depth/1305031936.031927.png
1305031936.068809 rgb/1305031936.068809.png 1305031936.063602 depth/1305031936.063602.png
1305031936.100718 rgb/1305031936.100718.png 1305031936.099066 depth/1305031936.099066.png
1305031936.137490 rgb/1305031936.137490.png 1305031936.130808 depth/1305031936.130808.png
1305031936.168897 rgb/1305031936.168897.png 1305031936.163443 depth/1305031936.163443.png
1305031936.200867 rgb/1305031936.200867.png 1305031936.200045 depth/1305031936.200045.png
1305031936.237546 rgb/1305031936.237546.png 1305031936.231637 depth/1305031936.231637.png
1305031936.268981 rgb/1305031936.268981.png 1305031936.262854 depth/1305031936.262854.png
1305031936.300816 rgb/1305031936.300816.png 1305031936.299656 depth/1305031936.299656.png
1305031936.336863 rgb/1305031936.336863.png 1305031936.331649 depth/1305031936.331649.png
1305031936.368927 rgb/1305031936.368927.png 1305031936.363578 depth/1305031936.363578.png
1305031936.400840 rgb/1305031936.400840.png 1305031936.399525 depth/1305031936.399525.png
1305031936.436777 rgb/1305031936.436777.png 1305031936.431784 depth/1305031936.431784.png
1305031936.468789 rgb/1305031936.468789.png 1305031936.463134 depth/1305031936.463134.png
1305031936.500753 rgb/1305031936.500753.png 1305031936.499445 depth/1305031936.499445.png
1305031936.536847 rgb/1305031936.536847.png 1305031936.531202 depth/1305031936.531202.png
1305031936.569452 rgb/1305031936.569452.png 1305031936.563251 depth/1305031936.563251.png
1305031936.600821 rgb/1305031936.600821.png 1305031936.599685 depth/1305031936.599685.png
1305031936.636879 rgb/1305031936.636879.png 1305031936.631518 depth/1305031936.631518.png
1305031936.668885 rgb/1305031936.668885.png 1305031936.663832 depth/1305031936.663832.png
1305031936.700881 rgb/1305031936.700881.png 1305031936.699970 depth/1305031936.699970.png
1305031936.737504 rgb/1305031936.737504.png 1305031936.731597 depth/1305031936.731597.png
1305031936.768825 rgb/1305031936.768825.png 1305031936.763730 depth/1305031936.763730.png
1305031936.800856 rgb/1305031936.800856.png 1305031936.799809 depth/1305031936.799809.png
1305031936.836845 rgb/1305031936.836845.png 1305031936.831892 depth/1305031936.831892.png
1305031936.868891 rgb/1305031936.868891.png 1305031936.863697 depth/1305031936.863697.png
1305031936.900833 rgb/1305031936.900833.png 1305031936.900115 depth/1305031936.900115.png
1305031936.936914 rgb/1305031936.936914.png 1305031936.931480 depth/1305031936.931480.png
1305031936.968821 rgb/1305031936.968821.png 1305031936.963897 depth/1305031936.963897.png
1305031937.001118 rgb/1305031937.001118.png 1305031937.000148 depth/1305031937.000148.png
1305031937.036874 rgb/1305031937.036874.png 1305031937.032120 depth/1305031937.032120.png
1305031937.068765 rgb/1305031937.068765.png 1305031937.060179 depth/1305031937.060179.png
1305031937.100716 rgb/1305031937.100716.png 1305031937.097948 depth/1305031937.097948.png
1305031937.136838 rgb/1305031937.136838.png 1305031937.131381 depth/1305031937.131381.png
1305031937.168856 rgb/1305031937.168856.png 1305031937.162199 depth/1305031937.162199.png
1305031937.200813 rgb/1305031937.200813.png 1305031937.199678 depth/1305031937.199678.png
1305031937.236893 rgb/1305031937.236893.png 1305031937.231385 depth/1305031937.231385.png
1305031937.268821 rgb/1305031937.268821.png 1305031937.263361 depth/1305031937.263361.png
1305031937.300783 rgb/1305031937.300783.png 1305031937.299172 depth/1305031937.299172.png
1305031937.336862 rgb/1305031937.336862.png 1305031937.331472 depth/1305031937.331472.png
1305031937.368734 rgb/1305031937.368734.png 1305031937.367035 depth/1305031937.367035.png
1305031937.400796 rgb/1305031937.400796.png 1305031937.399644 depth/1305031937.399644.png
1305031937.438211 rgb/1305031937.438211.png 1305031937.431305 depth/1305031937.431305.png
1305031937.468824 rgb/1305031937.468824.png 1305031937.467256 depth/1305031937.467256.png
1305031937.500797 rgb/1305031937.500797.png 1305031937.499237 depth/1305031937.499237.png
1305031937.536931 rgb/1305031937.536931.png 1305031937.531606 depth/1305031937.531606.png
1305031937.568829 rgb/1305031937.568829.png 1305031937.566400 depth/1305031937.566400.png
1305031937.600746 rgb/1305031937.600746.png 1305031937.599586 depth/1305031937.599586.png
1305031937.636891 rgb/1305031937.636891.png 1305031937.627766 depth/1305031937.627766.png
1305031937.668803 rgb/1305031937.668803.png 1305031937.667658 depth/1305031937.667658.png
1305031937.700837 rgb/1305031937.700837.png 1305031937.699645 depth/1305031937.699645.png
1305031937.736899 rgb/1305031937.736899.png 1305031937.731732 depth/1305031937.731732.png
1305031937.768919 rgb/1305031937.768919.png 1305031937.767791 depth/1305031937.767791.png
1305031937.800834 rgb/1305031937.800834.png 1305031937.799732 depth/1305031937.799732.png
1305031937.836877 rgb/1305031937.836877.png 1305031937.831889 depth/1305031937.831889.png
1305031937.868807 rgb/1305031937.868807.png 1305031937.867758 depth/1305031937.867758.png
1305031937.900823 rgb/1305031937.900823.png 1305031937.899933 depth/1305031937.899933.png
1305031937.936960 rgb/1305031937.936960.png 1305031937.931831 depth/1305031937.931831.png
1305031937.968830 rgb/1305031937.968830.png 1305031937.968127 depth/1305031937.968127.png
1305031938.000822 rgb/1305031938.000822.png 1305031938.000042 depth/1305031938.000042.png
1305031938.036945 rgb/1305031938.036945.png 1305031938.031836 depth/1305031938.031836.png
1305031938.068761 rgb/1305031938.068761.png 1305031938.067761 depth/1305031938.067761.png
1305031938.100744 rgb/1305031938.100744.png 1305031938.100010 depth/1305031938.100010.png
1305031938.136885 rgb/1305031938.136885.png 1305031938.131856 depth/1305031938.131856.png
1305031938.168914 rgb/1305031938.168914.png 1305031938.168307 depth/1305031938.168307.png
1305031938.200883 rgb/1305031938.200883.png 1305031938.199974 depth/1305031938.199974.png
1305031938.236878 rgb/1305031938.236878.png 1305031938.231649 depth/1305031938.231649.png
1305031938.268809 rgb/1305031938.268809.png 1305031938.267768 depth/1305031938.267768.png
1305031938.300837 rgb/1305031938.300837.png 1305031938.300089 depth/1305031938.300089.png
1305031938.336900 rgb/1305031938.336900.png 1305031938.331736 depth/1305031938.331736.png
1305031938.368914 rgb/1305031938.368914.png 1305031938.367715 depth/1305031938.367715.png
1305031938.400842 rgb/1305031938.400842.png 1305031938.400257 depth/1305031938.400257.png
1305031938.436889 rgb/1305031938.436889.png 1305031938.431934 depth/1305031938.431934.png
1305031938.468781 rgb/1305031938.468781.png 1305031938.468046 depth/1305031938.468046.png
1305031938.501288 rgb/1305031938.501288.png 1305031938.496114 depth/1305031938.496114.png
1305031938.537028 rgb/1305031938.537028.png 1305031938.535972 depth/1305031938.535972.png
1305031938.568999 rgb/1305031938.568999.png 1305031938.563904 depth/1305031938.563904.png
1305031938.601007 rgb/1305031938.601007.png 1305031938.598200 depth/1305031938.598200.png
1305031938.637299 rgb/1305031938.637299.png 1305031938.637455 depth/1305031938.637455.png
1305031938.668747 rgb/1305031938.668747.png 1305031938.667115 depth/1305031938.667115.png
1305031938.700851 rgb/1305031938.700851.png 1305031938.699613 depth/1305031938.699613.png
1305031938.736859 rgb/1305031938.736859.png 1305031938.735353 depth/1305031938.735353.png
1305031938.769073 rgb/1305031938.769073.png 1305031938.767438 depth/1305031938.767438.png
1305031938.800781 rgb/1305031938.800781.png 1305031938.799553 depth/1305031938.799553.png
1305031938.836754 rgb/1305031938.836754.png 1305031938.835081 depth/1305031938.835081.png
1305031938.869057 rgb/1305031938.869057.png 1305031938.867115 depth/1305031938.867115.png
1305031938.900976 rgb/1305031938.900976.png 1305031938.899948 depth/1305031938.899948.png
1305031938.936828 rgb/1305031938.936828.png 1305031938.935595 depth/1305031938.935595.png
1305031938.969026 rgb/1305031938.969026.png 1305031938.967685 depth/1305031938.967685.png
1305031939.001030 rgb/1305031939.001030.png 1305031939.000242 depth/1305031939.000242.png
1305031939.037090 rgb/1305031939.037090.png 1305031939.035825 depth/1305031939.035825.png
1305031939.069377 rgb/1305031939.069377.png 1305031939.067934 depth/1305031939.067934.png
1305031939.101368 rgb/1305031939.101368.png 1305031939.099862 depth/1305031939.099862.png
1305031939.137143 rgb/1305031939.137143.png 1305031939.135566 depth/1305031939.135566.png
1305031939.168815 rgb/1305031939.168815.png 1305031939.167694 depth/1305031939.167694.png
1305031939.200865 rgb/1305031939.200865.png 1305031939.200214 depth/1305031939.200214.png
1305031939.237165 rgb/1305031939.237165.png 1305031939.235712 depth/1305031939.235712.png
1305031939.268824 rgb/1305031939.268824.png 1305031939.267640 depth/1305031939.267640.png
1305031939.300842 rgb/1305031939.300842.png 1305031939.300206 depth/1305031939.300206.png
1305031939.336729 rgb/1305031939.336729.png 1305031939.335053 depth/1305031939.335053.png
1305031939.368966 rgb/1305031939.368966.png 1305031939.367490 depth/1305031939.367490.png
1305031939.400848 rgb/1305031939.400848.png 1305031939.399885 depth/1305031939.399885.png
1305031939.436845 rgb/1305031939.436845.png 1305031939.435410 depth/1305031939.435410.png
1305031939.468851 rgb/1305031939.468851.png 1305031939.467647 depth/1305031939.467647.png
1305031939.500839 rgb/1305031939.500839.png 1305031939.499844 depth/1305031939.499844.png
1305031939.536755 rgb/1305031939.536755.png 1305031939.535364 depth/1305031939.535364.png
1305031939.568772 rgb/1305031939.568772.png 1305031939.567564 depth/1305031939.567564.png
1305031939.600838 rgb/1305031939.600838.png 1305031939.600160 depth/1305031939.600160.png
1305031939.636792 rgb/1305031939.636792.png 1305031939.635762 depth/1305031939.635762.png
1305031939.668867 rgb/1305031939.668867.png 1305031939.667415 depth/1305031939.667415.png
1305031939.700830 rgb/1305031939.700830.png 1305031939.700124 depth/1305031939.700124.png
1305031939.736750 rgb/1305031939.736750.png 1305031939.735464 depth/1305031939.735464.png
1305031939.768919 rgb/1305031939.768919.png 1305031939.767882 depth/1305031939.767882.png
1305031939.803671 rgb/1305031939.803671.png 1305031939.803685 depth/1305031939.803685.png
1305031939.837145 rgb/1305031939.837145.png 1305031939.835759 depth/1305031939.835759.png
1305031939.869215 rgb/1305031939.869215.png 1305031939.863918 depth/1305031939.863918.png
1305031939.903633 rgb/1305031939.903633.png 1305031939.903642 depth/1305031939.903642.png
1305031939.937192 rgb/1305031939.937192.png 1305031939.936002 depth/1305031939.936002.png
1305031939.968904 rgb/1305031939.968904.png 1305031939.967674 depth/1305031939.967674.png
1305031940.005582 rgb/1305031940.005582.png 1305031940.005613 depth/1305031940.005613.png
1305031940.037088 rgb/1305031940.037088.png 1305031940.031897 depth/1305031940.031897.png
1305031940.068783 rgb/1305031940.068783.png 1305031940.067499 depth/1305031940.067499.png
1305031940.104265 rgb/1305031940.104265.png 1305031940.104322 depth/1305031940.104322.png
1305031940.136746 rgb/1305031940.136746.png 1305031940.135843 depth/1305031940.135843.png
1305031940.168737 rgb/1305031940.168737.png 1305031940.168748 depth/1305031940.168748.png
1305031940.200829 rgb/1305031940.200829.png 1305031940.200119 depth/1305031940.200119.png
1305031940.236742 rgb/1305031940.236742.png 1305031940.235303 depth/1305031940.235303.png
1305031940.269041 rgb/1305031940.269041.png 1305031940.267548 depth/1305031940.267548.png
1305031940.301146 rgb/1305031940.301146.png 1305031940.300057 depth/1305031940.300057.png
1305031940.336732 rgb/1305031940.336732.png 1305031940.335962 depth/1305031940.335962.png
1305031940.369236 rgb/1305031940.369236.png 1305031940.367240 depth/1305031940.367240.png
1305031940.403665 rgb/1305031940.403665.png 1305031940.403701 depth/1305031940.403701.png
1305031940.436756 rgb/1305031940.436756.png 1305031940.435753 depth/1305031940.435753.png
1305031940.468746 rgb/1305031940.468746.png 1305031940.467066 depth/1305031940.467066.png
1305031940.503804 rgb/1305031940.503804.png 1305031940.503814 depth/1305031940.503814.png
1305031940.536724 rgb/1305031940.536724.png 1305031940.535239 depth/1305031940.535239.png
1305031940.568758 rgb/1305031940.568758.png 1305031940.566964 depth/1305031940.566964.png
1305031940.603364 rgb/1305031940.603364.png 1305031940.603395 depth/1305031940.603395.png
1305031940.636761 rgb/1305031940.636761.png 1305031940.635226 depth/1305031940.635226.png
1305031940.668762 rgb/1305031940.668762.png 1305031940.666993 depth/1305031940.666993.png
1305031940.703222 rgb/1305031940.703222.png 1305031940.703234 depth/1305031940.703234.png
1305031940.736947 rgb/1305031940.736947.png 1305031940.735222 depth/1305031940.735222.png
1305031940.768772 rgb/1305031940.768772.png 1305031940.766929 depth/1305031940.766929.png
1305031940.803047 rgb/1305031940.803047.png 1305031940.803100 depth/1305031940.803100.png
1305031940.836755 rgb/1305031940.836755.png 1305031940.835097 depth/1305031940.835097.png
1305031940.869689 rgb/1305031940.869689.png 1305031940.867019 depth/1305031940.867019.png
1305031940.903305 rgb/1305031940.903305.png 1305031940.903314 depth/1305031940.903314.png
1305031940.937034 rgb/1305031940.937034.png 1305031940.935305 depth/1305031940.935305.png
1305031940.968758 rgb/1305031940.968758.png 1305031940.967150 depth/1305031940.967150.png
1305031941.003160 rgb/1305031941.003160.png 1305031941.003186 depth/1305031941.003186.png
1305031941.036777 rgb/1305031941.036777.png 1305031941.035260 depth/1305031941.035260.png
1305031941.071057 rgb/1305031941.071057.png 1305031941.071076 depth/1305031941.071076.png
1305031941.103422 rgb/1305031941.103422.png 1305031941.103456 depth/1305031941.103456.png
1305031941.136774 rgb/1305031941.136774.png 1305031941.135554 depth/1305031941.135554.png
1305031941.171144 rgb/1305031941.171144.png 1305031941.171171 depth/1305031941.171171.png
1305031941.203508 rgb/1305031941.203508.png 1305031941.203532 depth/1305031941.203532.png
1305031941.236705 rgb/1305031941.236705.png 1305031941.235196 depth/1305031941.235196.png
1305031941.271129 rgb/1305031941.271129.png 1305031941.271139 depth/1305031941.271139.png
1305031941.303362 rgb/1305031941.303362.png 1305031941.303377 depth/1305031941.303377.png
1305031941.336734 rgb/1305031941.336734.png 1305031941.335303 depth/1305031941.335303.png
1305031941.371607 rgb/1305031941.371607.png 1305031941.371617 depth/1305031941.371617.png
1305031941.403845 rgb/1305031941.403845.png 1305031941.403877 depth/1305031941.403877.png
1305031941.436799 rgb/1305031941.436799.png 1305031941.435687 depth/1305031941.435687.png
1305031941.469611 rgb/1305031941.469611.png 1305031941.469619 depth/1305031941.469619.png
1305031941.501458 rgb/1305031941.501458.png 1305031941.501518 depth/1305031941.501518.png
1305031941.537220 rgb/1305031941.537220.png 1305031941.534653 depth/1305031941.534653.png
1305031941.570287 rgb/1305031941.570287.png 1305031941.570302 depth/1305031941.570302.png
1305031941.603047 rgb/1305031941.603047.png 1305031941.603072 depth/1305031941.603072.png
1305031941.636822 rgb/1305031941.636822.png 1305031941.635675 depth/1305031941.635675.png
1305031941.671554 rgb/1305031941.671554.png 1305031941.671562 depth/1305031941.671562.png
1305031941.703763 rgb/1305031941.703763.png 1305031941.703773 depth/1305031941.703773.png
1305031941.736866 rgb/1305031941.736866.png 1305031941.735592 depth/1305031941.735592.png
1305031941.768815 rgb/1305031941.768815.png 1305031941.767812 depth/1305031941.767812.png
1305031941.800820 rgb/1305031941.800820.png 1305031941.800828 depth/1305031941.800828.png
1305031941.836848 rgb/1305031941.836848.png 1305031941.832014 depth/1305031941.832014.png
1305031941.871813 rgb/1305031941.871813.png 1305031941.871824 depth/1305031941.871824.png
1305031941.902976 rgb/1305031941.902976.png 1305031941.903043 depth/1305031941.903043.png
1305031941.936760 rgb/1305031941.936760.png 1305031941.935190 depth/1305031941.935190.png
1305031941.971057 rgb/1305031941.971057.png 1305031941.971085 depth/1305031941.971085.png
1305031942.003141 rgb/1305031942.003141.png 1305031942.003159 depth/1305031942.003159.png
1305031942.036729 rgb/1305031942.036729.png 1305031942.035444 depth/1305031942.035444.png
1305031942.071082 rgb/1305031942.071082.png 1305031942.071092 depth/1305031942.071092.png
1305031942.100691 rgb/1305031942.100691.png 1305031942.099769 depth/1305031942.099769.png
1305031942.136758 rgb/1305031942.136758.png 1305031942.135205 depth/1305031942.135205.png
1305031942.170749 rgb/1305031942.170749.png 1305031942.170762 depth/1305031942.170762.png
1305031942.203108 rgb/1305031942.203108.png 1305031942.203125 depth/1305031942.203125.png
1305031942.238994 rgb/1305031942.238994.png 1305031942.239026 depth/1305031942.239026.png
1305031942.271105 rgb/1305031942.271105.png 1305031942.271143 depth/1305031942.271143.png
1305031942.303257 rgb/1305031942.303257.png 1305031942.303198 depth/1305031942.303198.png
1305031942.337047 rgb/1305031942.337047.png 1305031942.335609 depth/1305031942.335609.png
1305031942.370761 rgb/1305031942.370761.png 1305031942.370779 depth/1305031942.370779.png
1305031942.402939 rgb/1305031942.402939.png 1305031942.402950 depth/1305031942.402950.png
1305031942.439262 rgb/1305031942.439262.png 1305031942.439272 depth/1305031942.439272.png
1305031942.471958 rgb/1305031942.471958.png 1305031942.472314 depth/1305031942.472314.png
1305031942.503553 rgb/1305031942.503553.png 1305031942.503687 depth/1305031942.503687.png
1305031942.539453 rgb/1305031942.539453.png 1305031942.539471 depth/1305031942.539471.png
1305031942.571867 rgb/1305031942.571867.png 1305031942.571873 depth/1305031942.571873.png
1305031942.601448 rgb/1305031942.601448.png 1305031942.601458 depth/1305031942.601458.png
1305031942.639942 rgb/1305031942.639942.png 1305031942.639952 depth/1305031942.639952.png
1305031942.669006 rgb/1305031942.669006.png 1305031942.667679 depth/1305031942.667679.png
1305031942.704015 rgb/1305031942.704015.png 1305031942.704026 depth/1305031942.704026.png
1305031942.739812 rgb/1305031942.739812.png 1305031942.739823 depth/1305031942.739823.png
1305031942.771708 rgb/1305031942.771708.png 1305031942.771728 depth/1305031942.771728.png
1305031942.801557 rgb/1305031942.801557.png 1305031942.801585 depth/1305031942.801585.png
1305031942.841042 rgb/1305031942.841042.png 1305031942.841069 depth/1305031942.841069.png
1305031942.868828 rgb/1305031942.868828.png 1305031942.867914 depth/1305031942.867914.png
1305031942.903960 rgb/1305031942.903960.png 1305031942.903971 depth/1305031942.903971.png
1305031942.936816 rgb/1305031942.936816.png 1305031942.936255 depth/1305031942.936255.png
1305031942.970936 rgb/1305031942.970936.png 1305031942.970947 depth/1305031942.970947.png
1305031943.001103 rgb/1305031943.001103.png 1305031943.001126 depth/1305031943.001126.png
1305031943.039961 rgb/1305031943.039961.png 1305031943.039973 depth/1305031943.039973.png
1305031943.071743 rgb/1305031943.071743.png 1305031943.071764 depth/1305031943.071764.png
1305031943.104177 rgb/1305031943.104177.png 1305031943.104196 depth/1305031943.104196.png
1305031943.139521 rgb/1305031943.139521.png 1305031943.139631 depth/1305031943.139631.png
1305031943.171912 rgb/1305031943.171912.png 1305031943.171931 depth/1305031943.171931.png
1305031943.201564 rgb/1305031943.201564.png 1305031943.201583 depth/1305031943.201583.png
1305031943.240004 rgb/1305031943.240004.png 1305031943.240026 depth/1305031943.240026.png
1305031943.271805 rgb/1305031943.271805.png 1305031943.272012 depth/1305031943.272012.png
1305031943.303965 rgb/1305031943.303965.png 1305031943.303977 depth/1305031943.303977.png
1305031943.339941 rgb/1305031943.339941.png 1305031943.339953 depth/1305031943.339953.png
1305031943.371774 rgb/1305031943.371774.png 1305031943.371795 depth/1305031943.371795.png
1305031943.404245 rgb/1305031943.404245.png 1305031943.404597 depth/1305031943.404597.png
1305031943.440153 rgb/1305031943.440153.png 1305031943.440230 depth/1305031943.440230.png
1305031943.471431 rgb/1305031943.471431.png 1305031943.471442 depth/1305031943.471442.png
1305031943.501108 rgb/1305031943.501108.png 1305031943.509496 depth/1305031943.509496.png
1305031943.539525 rgb/1305031943.539525.png 1305031943.539543 depth/1305031943.539543.png
1305031943.570021 rgb/1305031943.570021.png 1305031943.570040 depth/1305031943.570040.png
1305031943.607467 rgb/1305031943.607467.png 1305031943.607498 depth/1305031943.607498.png
1305031943.638026 rgb/1305031943.638026.png 1305031943.638034 depth/1305031943.638034.png
1305031943.671504 rgb/1305031943.671504.png 1305031943.671539 depth/1305031943.671539.png
1305031943.707251 rgb/1305031943.707251.png 1305031943.707262 depth/1305031943.707262.png
1305031943.739428 rgb/1305031943.739428.png 1305031943.739461 depth/1305031943.739461.png
1305031943.771329 rgb/1305031943.771329.png 1305031943.771360 depth/1305031943.771360.png
1305031943.806822 rgb/1305031943.806822.png 1305031943.806840 depth/1305031943.806840.png
1305031943.837754 rgb/1305031943.837754.png 1305031943.837771 depth/1305031943.837771.png
1305031943.868873 rgb/1305031943.868873.png 1305031943.867799 depth/1305031943.867799.png
1305031943.907218 rgb/1305031943.907218.png 1305031943.907228 depth/1305031943.907228.png
1305031943.936768 rgb/1305031943.936768.png 1305031943.935818 depth/1305031943.935818.png
1305031943.971278 rgb/1305031943.971278.png 1305031943.971293 depth/1305031943.971293.png
1305031944.007760 rgb/1305031944.007760.png 1305031944.007774 depth/1305031944.007774.png
1305031944.040486 rgb/1305031944.040486.png 1305031944.040559 depth/1305031944.040559.png
1305031944.070886 rgb/1305031944.070886.png 1305031944.070907 depth/1305031944.070907.png
1305031944.107390 rgb/1305031944.107390.png 1305031944.107412 depth/1305031944.107412.png
1305031944.139656 rgb/1305031944.139656.png 1305031944.139679 depth/1305031944.139679.png
1305031944.171370 rgb/1305031944.171370.png 1305031944.171401 depth/1305031944.171401.png
1305031944.206998 rgb/1305031944.206998.png 1305031944.207026 depth/1305031944.207026.png
1305031944.239334 rgb/1305031944.239334.png 1305031944.239359 depth/1305031944.239359.png
1305031944.270963 rgb/1305031944.270963.png 1305031944.270986 depth/1305031944.270986.png
1305031944.306934 rgb/1305031944.306934.png 1305031944.306965 depth/1305031944.306965.png
1305031944.339308 rgb/1305031944.339308.png 1305031944.339327 depth/1305031944.339327.png
1305031944.370745 rgb/1305031944.370745.png 1305031944.370764 depth/1305031944.370764.png
1305031944.406233 rgb/1305031944.406233.png 1305031944.406240 depth/1305031944.406240.png
1305031944.438724 rgb/1305031944.438724.png 1305031944.438740 depth/1305031944.438740.png
1305031944.471304 rgb/1305031944.471304.png 1305031944.471315 depth/1305031944.471315.png
1305031944.506947 rgb/1305031944.506947.png 1305031944.506966 depth/1305031944.506966.png
1305031944.539069 rgb/1305031944.539069.png 1305031944.539090 depth/1305031944.539090.png
1305031944.571530 rgb/1305031944.571530.png 1305031944.571543 depth/1305031944.571543.png
1305031944.607229 rgb/1305031944.607229.png 1305031944.607255 depth/1305031944.607255.png
1305031944.639625 rgb/1305031944.639625.png 1305031944.639988 depth/1305031944.639988.png
1305031944.671779 rgb/1305031944.671779.png 1305031944.671797 depth/1305031944.671797.png
1305031944.707774 rgb/1305031944.707774.png 1305031944.707795 depth/1305031944.707795.png
1305031944.739941 rgb/1305031944.739941.png 1305031944.739963 depth/1305031944.739963.png
1305031944.769058 rgb/1305031944.769058.png 1305031944.780883 depth/1305031944.780883.png
1305031944.807919 rgb/1305031944.807919.png 1305031944.807934 depth/1305031944.807934.png
1305031944.839956 rgb/1305031944.839956.png 1305031944.839961 depth/1305031944.839961.png
1305031944.875719 rgb/1305031944.875719.png 1305031944.875727 depth/1305031944.875727.png
1305031944.904670 rgb/1305031944.904670.png 1305031944.903822 depth/1305031944.903822.png
1305031944.939702 rgb/1305031944.939702.png 1305031944.939709 depth/1305031944.939709.png
1305031944.969076 rgb/1305031944.969076.png 1305031944.979551 depth/1305031944.979551.png
1305031945.007437 rgb/1305031945.007437.png 1305031945.007456 depth/1305031945.007456.png
1305031945.039937 rgb/1305031945.039937.png 1305031945.039953 depth/1305031945.039953.png
1305031945.069177 rgb/1305031945.069177.png 1305031945.079450 depth/1305031945.079450.png
1305031945.107523 rgb/1305031945.107523.png 1305031945.107554 depth/1305031945.107554.png
1305031945.136772 rgb/1305031945.136772.png 1305031945.135938 depth/1305031945.135938.png
1305031945.168992 rgb/1305031945.168992.png 1305031945.179287 depth/1305031945.179287.png
1305031945.207107 rgb/1305031945.207107.png 1305031945.207131 depth/1305031945.207131.png
1305031945.238859 rgb/1305031945.238859.png 1305031945.238880 depth/1305031945.238880.png
1305031945.269070 rgb/1305031945.269070.png 1305031945.276136 depth/1305031945.276136.png
1305031945.306358 rgb/1305031945.306358.png 1305031945.306364 depth/1305031945.306364.png
1305031945.338940 rgb/1305031945.338940.png 1305031945.338954 depth/1305031945.338954.png
1305031945.369056 rgb/1305031945.369056.png 1305031945.374695 depth/1305031945.374695.png
1305031945.406657 rgb/1305031945.406657.png 1305031945.406595 depth/1305031945.406595.png
1305031945.436818 rgb/1305031945.436818.png 1305031945.435557 depth/1305031945.435557.png
1305031945.469167 rgb/1305031945.469167.png 1305031945.477504 depth/1305031945.477504.png
1305031945.506438 rgb/1305031945.506438.png 1305031945.506448 depth/1305031945.506448.png
1305031945.538422 rgb/1305031945.538422.png 1305031945.538432 depth/1305031945.538432.png
1305031945.569071 rgb/1305031945.569071.png 1305031945.575422 depth/1305031945.575422.png
1305031945.606029 rgb/1305031945.606029.png 1305031945.606045 depth/1305031945.606045.png
1305031945.638298 rgb/1305031945.638298.png 1305031945.638328 depth/1305031945.638328.png
1305031945.669116 rgb/1305031945.669116.png 1305031945.677317 depth/1305031945.677317.png
1305031945.706215 rgb/1305031945.706215.png 1305031945.706227 depth/1305031945.706227.png
1305031945.738673 rgb/1305031945.738673.png 1305031945.738707 depth/1305031945.738707.png
1305031945.769045 rgb/1305031945.769045.png 1305031945.772817 depth/1305031945.772817.png
1305031945.806240 rgb/1305031945.806240.png 1305031945.806249 depth/1305031945.806249.png
1305031945.838266 rgb/1305031945.838266.png 1305031945.838302 depth/1305031945.838302.png
1305031945.869258 rgb/1305031945.869258.png 1305031945.877342 depth/1305031945.877342.png
1305031945.909177 rgb/1305031945.909177.png 1305031945.909465 depth/1305031945.909465.png
1305031945.936806 rgb/1305031945.936806.png 1305031945.935652 depth/1305031945.935652.png
1305031945.969300 rgb/1305031945.969300.png 1305031945.977263 depth/1305031945.977263.png
1305031946.005983 rgb/1305031946.005983.png 1305031946.005994 depth/1305031946.005994.png
1305031946.037278 rgb/1305031946.037278.png 1305031946.043263 depth/1305031946.043263.png
1305031946.069057 rgb/1305031946.069057.png 1305031946.075402 depth/1305031946.075402.png
1305031946.107140 rgb/1305031946.107140.png 1305031946.107156 depth/1305031946.107156.png
1305031946.137054 rgb/1305031946.137054.png 1305031946.147686 depth/1305031946.147686.png
1305031946.168867 rgb/1305031946.168867.png 1305031946.175861 depth/1305031946.175861.png
1305031946.207043 rgb/1305031946.207043.png 1305031946.207053 depth/1305031946.207053.png
1305031946.237369 rgb/1305031946.237369.png 1305031946.247192 depth/1305031946.247192.png
1305031946.268902 rgb/1305031946.268902.png 1305031946.276972 depth/1305031946.276972.png
1305031946.306775 rgb/1305031946.306775.png 1305031946.306937 depth/1305031946.306937.png
1305031946.337036 rgb/1305031946.337036.png 1305031946.347086 depth/1305031946.347086.png
1305031946.369021 rgb/1305031946.369021.png 1305031946.378747 depth/1305031946.378747.png
1305031946.406520 rgb/1305031946.406520.png 1305031946.406531 depth/1305031946.406531.png
1305031946.437150 rgb/1305031946.437150.png 1305031946.447353 depth/1305031946.447353.png
1305031946.468964 rgb/1305031946.468964.png 1305031946.473076 depth/1305031946.473076.png
1305031946.506586 rgb/1305031946.506586.png 1305031946.506597 depth/1305031946.506597.png
1305031946.537148 rgb/1305031946.537148.png 1305031946.546018 depth/1305031946.546018.png
1305031946.569238 rgb/1305031946.569238.png 1305031946.577280 depth/1305031946.577280.png
1305031946.606469 rgb/1305031946.606469.png 1305031946.606485 depth/1305031946.606485.png
1305031946.637163 rgb/1305031946.637163.png 1305031946.645981 depth/1305031946.645981.png
1305031946.669089 rgb/1305031946.669089.png 1305031946.678050 depth/1305031946.678050.png
1305031946.706515 rgb/1305031946.706515.png 1305031946.706532 depth/1305031946.706532.png
1305031946.737134 rgb/1305031946.737134.png 1305031946.743717 depth/1305031946.743717.png
1305031946.769059 rgb/1305031946.769059.png 1305031946.774660 depth/1305031946.774660.png
1305031946.806647 rgb/1305031946.806647.png 1305031946.806659 depth/1305031946.806659.png
1305031946.837100 rgb/1305031946.837100.png 1305031946.842679 depth/1305031946.842679.png
1305031946.869090 rgb/1305031946.869090.png 1305031946.874721 depth/1305031946.874721.png
1305031946.906602 rgb/1305031946.906602.png 1305031946.906633 depth/1305031946.906633.png
1305031946.937151 rgb/1305031946.937151.png 1305031946.942686 depth/1305031946.942686.png
1305031946.969064 rgb/1305031946.969064.png 1305031946.974825 depth/1305031946.974825.png
1305031947.006827 rgb/1305031947.006827.png 1305031947.006833 depth/1305031947.006833.png
1305031947.037000 rgb/1305031947.037000.png 1305031947.042914 depth/1305031947.042914.png
1305031947.068973 rgb/1305031947.068973.png 1305031947.074589 depth/1305031947.074589.png
1305031947.106644 rgb/1305031947.106644.png 1305031947.106663 depth/1305031947.106663.png
1305031947.137044 rgb/1305031947.137044.png 1305031947.142937 depth/1305031947.142937.png
1305031947.169117 rgb/1305031947.169117.png 1305031947.174651 depth/1305031947.174651.png
1305031947.204982 rgb/1305031947.204982.png 1305031947.210803 depth/1305031947.210803.png
1305031947.237001 rgb/1305031947.237001.png 1305031947.242625 depth/1305031947.242625.png
1305031947.269076 rgb/1305031947.269076.png 1305031947.274786 depth/1305031947.274786.png
1305031947.304951 rgb/1305031947.304951.png 1305031947.309122 depth/1305031947.309122.png
1305031947.336945 rgb/1305031947.336945.png 1305031947.339718 depth/1305031947.339718.png
1305031947.368991 rgb/1305031947.368991.png 1305031947.373087 depth/1305031947.373087.png
1305031947.405013 rgb/1305031947.405013.png 1305031947.407848 depth/1305031947.407848.png
1305031947.437038 rgb/1305031947.437038.png 1305031947.442996 depth/1305031947.442996.png
1305031947.469273 rgb/1305031947.469273.png 1305031947.475248 depth/1305031947.475248.png
1305031947.504994 rgb/1305031947.504994.png 1305031947.511457 depth/1305031947.511457.png
1305031947.537022 rgb/1305031947.537022.png 1305031947.543322 depth/1305031947.543322.png
1305031947.568989 rgb/1305031947.568989.png 1305031947.572475 depth/1305031947.572475.png
1305031947.605177 rgb/1305031947.605177.png 1305031947.611625 depth/1305031947.611625.png
1305031947.637085 rgb/1305031947.637085.png 1305031947.643731 depth/1305031947.643731.png
1305031947.669011 rgb/1305031947.669011.png 1305031947.675360 depth/1305031947.675360.png
1305031947.705153 rgb/1305031947.705153.png 1305031947.711025 depth/1305031947.711025.png
1305031947.736979 rgb/1305031947.736979.png 1305031947.743304 depth/1305031947.743304.png
1305031947.769041 rgb/1305031947.769041.png 1305031947.775461 depth/1305031947.775461.png
1305031947.804941 rgb/1305031947.804941.png 1305031947.811424 depth/1305031947.811424.png
1305031947.837022 rgb/1305031947.837022.png 1305031947.841415 depth/1305031947.841415.png
1305031947.868988 rgb/1305031947.868988.png 1305031947.875442 depth/1305031947.875442.png
1305031947.904995 rgb/1305031947.904995.png 1305031947.911295 depth/1305031947.911295.png
1305031947.937025 rgb/1305031947.937025.png 1305031947.943516 depth/1305031947.943516.png
1305031947.968976 rgb/1305031947.968976.png 1305031947.975273 depth/1305031947.975273.png
1305031948.004911 rgb/1305031948.004911.png 1305031948.011498 depth/1305031948.011498.png
1305031948.037003 rgb/1305031948.037003.png 1305031948.043239 depth/1305031948.043239.png
1305031948.068973 rgb/1305031948.068973.png 1305031948.075218 depth/1305031948.075218.png
1305031948.104993 rgb/1305031948.104993.png 1305031948.111315 depth/1305031948.111315.png
1305031948.136951 rgb/1305031948.136951.png 1305031948.143226 depth/1305031948.143226.png
1305031948.168952 rgb/1305031948.168952.png 1305031948.175007 depth/1305031948.175007.png
1305031948.204992 rgb/1305031948.204992.png 1305031948.211235 depth/1305031948.211235.png
1305031948.237002 rgb/1305031948.237002.png 1305031948.243210 depth/1305031948.243210.png
1305031948.269041 rgb/1305031948.269041.png 1305031948.275446 depth/1305031948.275446.png
1305031948.304939 rgb/1305031948.304939.png 1305031948.311425 depth/1305031948.311425.png
1305031948.337101 rgb/1305031948.337101.png 1305031948.343521 depth/1305031948.343521.png
1305031948.368969 rgb/1305031948.368969.png 1305031948.375447 depth/1305031948.375447.png
1305031948.404989 rgb/1305031948.404989.png 1305031948.411285 depth/1305031948.411285.png
1305031948.436942 rgb/1305031948.436942.png 1305031948.443647 depth/1305031948.443647.png
1305031948.469170 rgb/1305031948.469170.png 1305031948.480437 depth/1305031948.480437.png
1305031948.505024 rgb/1305031948.505024.png 1305031948.514284 depth/1305031948.514284.png
1305031948.537017 rgb/1305031948.537017.png 1305031948.542869 depth/1305031948.542869.png
1305031948.568891 rgb/1305031948.568891.png 1305031948.580687 depth/1305031948.580687.png
1305031948.605001 rgb/1305031948.605001.png 1305031948.611060 depth/1305031948.611060.png
1305031948.636912 rgb/1305031948.636912.png 1305031948.644895 depth/1305031948.644895.png
1305031948.669040 rgb/1305031948.669040.png 1305031948.681662 depth/1305031948.681662.png
1305031948.705075 rgb/1305031948.705075.png 1305031948.714453 depth/1305031948.714453.png
1305031948.737063 rgb/1305031948.737063.png 1305031948.746432 depth/1305031948.746432.png
1305031948.768899 rgb/1305031948.768899.png 1305031948.780858 depth/1305031948.780858.png
1305031948.804975 rgb/1305031948.804975.png 1305031948.812389 depth/1305031948.812389.png
1305031948.837073 rgb/1305031948.837073.png 1305031948.841687 depth/1305031948.841687.png
1305031948.868835 rgb/1305031948.868835.png 1305031948.880529 depth/1305031948.880529.png
1305031948.905077 rgb/1305031948.905077.png 1305031948.915493 depth/1305031948.915493.png
1305031948.936996 rgb/1305031948.936996.png 1305031948.943231 depth/1305031948.943231.png
1305031948.968952 rgb/1305031948.968952.png 1305031948.979038 depth/1305031948.979038.png
1305031949.005006 rgb/1305031949.005006.png 1305031949.014896 depth/1305031949.014896.png
1305031949.037089 rgb/1305031949.037089.png 1305031949.044596 depth/1305031949.044596.png
1305031949.069061 rgb/1305031949.069061.png 1305031949.082201 depth/1305031949.082201.png
1305031949.105077 rgb/1305031949.105077.png 1305031949.114284 depth/1305031949.114284.png
1305031949.137263 rgb/1305031949.137263.png 1305031949.144262 depth/1305031949.144262.png
1305031949.168946 rgb/1305031949.168946.png 1305031949.180779 depth/1305031949.180779.png
1305031949.204940 rgb/1305031949.204940.png 1305031949.214247 depth/1305031949.214247.png
1305031949.237011 rgb/1305031949.237011.png 1305031949.247701 depth/1305031949.247701.png
1305031949.268994 rgb/1305031949.268994.png 1305031949.281444 depth/1305031949.281444.png
1305031949.305254 rgb/1305031949.305254.png 1305031949.311257 depth/1305031949.311257.png
1305031949.337227 rgb/1305031949.337227.png 1305031949.341972 depth/1305031949.341972.png
1305031949.368902 rgb/1305031949.368902.png 1305031949.380234 depth/1305031949.380234.png
1305031949.405064 rgb/1305031949.405064.png 1305031949.410764 depth/1305031949.410764.png
1305031949.437094 rgb/1305031949.437094.png 1305031949.443117 depth/1305031949.443117.png
1305031949.468902 rgb/1305031949.468902.png 1305031949.479260 depth/1305031949.479260.png
1305031949.505002 rgb/1305031949.505002.png 1305031949.510843 depth/1305031949.510843.png
1305031949.537017 rgb/1305031949.537017.png 1305031949.541920 depth/1305031949.541920.png
1305031949.568988 rgb/1305031949.568988.png 1305031949.580836 depth/1305031949.580836.png
1305031949.604798 rgb/1305031949.604798.png 1305031949.614433 depth/1305031949.614433.png
1305031949.637172 rgb/1305031949.637172.png 1305031949.646345 depth/1305031949.646345.png
1305031949.668955 rgb/1305031949.668955.png 1305031949.680760 depth/1305031949.680760.png
1305031949.705003 rgb/1305031949.705003.png 1305031949.714490 depth/1305031949.714490.png
1305031949.736949 rgb/1305031949.736949.png 1305031949.749412 depth/1305031949.749412.png
1305031949.768985 rgb/1305031949.768985.png 1305031949.781235 depth/1305031949.781235.png
1305031949.804939 rgb/1305031949.804939.png 1305031949.811436 depth/1305031949.811436.png
1305031949.836964 rgb/1305031949.836964.png 1305031949.845215 depth/1305031949.845215.png
1305031949.868951 rgb/1305031949.868951.png 1305031949.880626 depth/1305031949.880626.png
1305031949.904851 rgb/1305031949.904851.png 1305031949.914703 depth/1305031949.914703.png
1305031949.936858 rgb/1305031949.936858.png 1305031949.948731 depth/1305031949.948731.png
1305031949.968881 rgb/1305031949.968881.png 1305031949.981207 depth/1305031949.981207.png
1305031950.004952 rgb/1305031950.004952.png 1305031950.011524 depth/1305031950.011524.png
1305031950.036989 rgb/1305031950.036989.png 1305031950.047520 depth/1305031950.047520.png
1305031950.069081 rgb/1305031950.069081.png 1305031950.080195 depth/1305031950.080195.png
1305031950.104966 rgb/1305031950.104966.png 1305031950.111190 depth/1305031950.111190.png
1305031950.136997 rgb/1305031950.136997.png 1305031950.147985 depth/1305031950.147985.png
1305031950.168914 rgb/1305031950.168914.png 1305031950.181754 depth/1305031950.181754.png
1305031950.204933 rgb/1305031950.204933.png 1305031950.211149 depth/1305031950.211149.png
1305031950.237027 rgb/1305031950.237027.png 1305031950.247238 depth/1305031950.247238.png
1305031950.269033 rgb/1305031950.269033.png 1305031950.279213 depth/1305031950.279213.png
1305031950.304978 rgb/1305031950.304978.png 1305031950.307722 depth/1305031950.307722.png
1305031950.337197 rgb/1305031950.337197.png 1305031950.346992 depth/1305031950.346992.png
1305031950.368911 rgb/1305031950.368911.png 1305031950.378386 depth/1305031950.378386.png
1305031950.404939 rgb/1305031950.404939.png 1305031950.410330 depth/1305031950.410330.png
1305031950.436983 rgb/1305031950.436983.png 1305031950.447451 depth/1305031950.447451.png
1305031950.468976 rgb/1305031950.468976.png 1305031950.478952 depth/1305031950.478952.png
1305031950.504938 rgb/1305031950.504938.png 1305031950.510402 depth/1305031950.510402.png
1305031950.536894 rgb/1305031950.536894.png 1305031950.546397 depth/1305031950.546397.png
1305031950.568883 rgb/1305031950.568883.png 1305031950.578462 depth/1305031950.578462.png
1305031950.604862 rgb/1305031950.604862.png 1305031950.610212 depth/1305031950.610212.png
1305031950.637006 rgb/1305031950.637006.png 1305031950.646840 depth/1305031950.646840.png
1305031950.668910 rgb/1305031950.668910.png 1305031950.678650 depth/1305031950.678650.png
1305031950.704873 rgb/1305031950.704873.png 1305031950.707517 depth/1305031950.707517.png
1305031950.736893 rgb/1305031950.736893.png 1305031950.746448 depth/1305031950.746448.png
1305031950.768897 rgb/1305031950.768897.png 1305031950.778662 depth/1305031950.778662.png
1305031950.804899 rgb/1305031950.804899.png 1305031950.810641 depth/1305031950.810641.png
1305031950.837135 rgb/1305031950.837135.png 1305031950.846960 depth/1305031950.846960.png
1305031950.869014 rgb/1305031950.869014.png 1305031950.880523 depth/1305031950.880523.png
1305031950.904883 rgb/1305031950.904883.png 1305031950.914994 depth/1305031950.914994.png
1305031950.936970 rgb/1305031950.936970.png 1305031950.948166 depth/1305031950.948166.png
1305031950.968904 rgb/1305031950.968904.png 1305031950.978853 depth/1305031950.978853.png
1305031951.004836 rgb/1305031951.004836.png 1305031951.016385 depth/1305031951.016385.png
1305031951.036930 rgb/1305031951.036930.png 1305031951.048065 depth/1305031951.048065.png
1305031951.069013 rgb/1305031951.069013.png 1305031951.080859 depth/1305031951.080859.png
1305031951.104800 rgb/1305031951.104800.png 1305031951.116229 depth/1305031951.116229.png
1305031951.136893 rgb/1305031951.136893.png 1305031951.147131 depth/1305031951.147131.png
1305031951.168908 rgb/1305031951.168908.png 1305031951.180627 depth/1305031951.180627.png
1305031951.204914 rgb/1305031951.204914.png 1305031951.215695 depth/1305031951.215695.png
1305031951.236957 rgb/1305031951.236957.png 1305031951.247998 depth/1305031951.247998.png
1305031951.268906 rgb/1305031951.268906.png 1305031951.279729 depth/1305031951.279729.png
1305031951.304862 rgb/1305031951.304862.png 1305031951.316576 depth/1305031951.316576.png
1305031951.336937 rgb/1305031951.336937.png 1305031951.348921 depth/1305031951.348921.png
1305031951.368840 rgb/1305031951.368840.png 1305031951.380780 depth/1305031951.380780.png
1305031951.404865 rgb/1305031951.404865.png 1305031951.415739 depth/1305031951.415739.png
1305031951.436903 rgb/1305031951.436903.png 1305031951.448724 depth/1305031951.448724.png
1305031951.468857 rgb/1305031951.468857.png 1305031951.479264 depth/1305031951.479264.png
1305031951.504916 rgb/1305031951.504916.png 1305031951.514325 depth/1305031951.514325.png
1305031951.536888 rgb/1305031951.536888.png 1305031951.549086 depth/1305031951.549086.png
1305031951.569006 rgb/1305031951.569006.png 1305031951.579884 depth/1305031951.579884.png
1305031951.604927 rgb/1305031951.604927.png 1305031951.616005 depth/1305031951.616005.png
1305031951.636936 rgb/1305031951.636936.png 1305031951.647946 depth/1305031951.647946.png
1305031951.668929 rgb/1305031951.668929.png 1305031951.680049 depth/1305031951.680049.png
1305031951.704880 rgb/1305031951.704880.png 1305031951.715829 depth/1305031951.715829.png
1305031951.736828 rgb/1305031951.736828.png 1305031951.747698 depth/1305031951.747698.png
1305031951.768926 rgb/1305031951.768926.png 1305031951.779676 depth/1305031951.779676.png
1305031951.804886 rgb/1305031951.804886.png 1305031951.813548 depth/1305031951.813548.png
1305031951.836932 rgb/1305031951.836932.png 1305031951.848226 depth/1305031951.848226.png
1305031951.868913 rgb/1305031951.868913.png 1305031951.880079 depth/1305031951.880079.png
1305031951.904907 rgb/1305031951.904907.png 1305031951.915908 depth/1305031951.915908.png
1305031951.936962 rgb/1305031951.936962.png 1305031951.948683 depth/1305031951.948683.png
1305031951.968839 rgb/1305031951.968839.png 1305031951.981889 depth/1305031951.981889.png
1305031952.004839 rgb/1305031952.004839.png 1305031952.016974 depth/1305031952.016974.png
1305031952.037104 rgb/1305031952.037104.png 1305031952.048200 depth/1305031952.048200.png
1305031952.068888 rgb/1305031952.068888.png 1305031952.080085 depth/1305031952.080085.png
1305031952.105135 rgb/1305031952.105135.png 1305031952.116717 depth/1305031952.116717.png
1305031952.136943 rgb/1305031952.136943.png 1305031952.147987 depth/1305031952.147987.png
1305031952.168932 rgb/1305031952.168932.png 1305031952.184234 depth/1305031952.184234.png
1305031952.204914 rgb/1305031952.204914.png 1305031952.216761 depth/1305031952.216761.png
1305031952.236877 rgb/1305031952.236877.png 1305031952.249227 depth/1305031952.249227.png
1305031952.268902 rgb/1305031952.268902.png 1305031952.286014 depth/1305031952.286014.png
1305031952.304888 rgb/1305031952.304888.png 1305031952.316634 depth/1305031952.316634.png
1305031952.336993 rgb/1305031952.336993.png 1305031952.348255 depth/1305031952.348255.png
1305031952.368960 rgb/1305031952.368960.png 1305031952.384145 depth/1305031952.384145.png
1305031952.404918 rgb/1305031952.404918.png 1305031952.416972 depth/1305031952.416972.png
1305031952.437054 rgb/1305031952.437054.png 1305031952.448757 depth/1305031952.448757.png
1305031952.468939 rgb/1305031952.468939.png 1305031952.485298 depth/1305031952.485298.png
1305031952.504868 rgb/1305031952.504868.png 1305031952.517162 depth/1305031952.517162.png
1305031952.536948 rgb/1305031952.536948.png 1305031952.549624 depth/1305031952.549624.png
1305031952.568932 rgb/1305031952.568932.png 1305031952.586036 depth/1305031952.586036.png
1305031952.604926 rgb/1305031952.604926.png 1305031952.616651 depth/1305031952.616651.png
1305031952.636992 rgb/1305031952.636992.png 1305031952.648319 depth/1305031952.648319.png
1305031952.668899 rgb/1305031952.668899.png 1305031952.684311 depth/1305031952.684311.png
1305031952.704918 rgb/1305031952.704918.png 1305031952.716954 depth/1305031952.716954.png
1305031952.736938 rgb/1305031952.736938.png 1305031952.747932 depth/1305031952.747932.png
1305031952.768957 rgb/1305031952.768957.png 1305031952.784923 depth/1305031952.784923.png
1305031952.804919 rgb/1305031952.804919.png 1305031952.815896 depth/1305031952.815896.png
1305031952.836931 rgb/1305031952.836931.png 1305031952.848902 depth/1305031952.848902.png
1305031952.868991 rgb/1305031952.868991.png 1305031952.884506 depth/1305031952.884506.png
1305031952.904920 rgb/1305031952.904920.png 1305031952.916053 depth/1305031952.916053.png
1305031952.936984 rgb/1305031952.936984.png 1305031952.947523 depth/1305031952.947523.png
1305031952.972903 rgb/1305031952.972903.png 1305031952.984578 depth/1305031952.984578.png
1305031953.004869 rgb/1305031953.004869.png 1305031953.016595 depth/1305031953.016595.png
1305031953.036943 rgb/1305031953.036943.png 1305031953.049017 depth/1305031953.049017.png
1305031953.073127 rgb/1305031953.073127.png 1305031953.083674 depth/1305031953.083674.png
1305031953.104909 rgb/1305031953.104909.png 1305031953.115587 depth/1305031953.115587.png
1305031953.137098 rgb/1305031953.137098.png 1305031953.147161 depth/1305031953.147161.png
1305031953.172998 rgb/1305031953.172998.png 1305031953.183058 depth/1305031953.183058.png
1305031953.204992 rgb/1305031953.204992.png 1305031953.215053 depth/1305031953.215053.png
1305031953.237103 rgb/1305031953.237103.png 1305031953.248151 depth/1305031953.248151.png
1305031953.273087 rgb/1305031953.273087.png 1305031953.283786 depth/1305031953.283786.png
1305031953.304968 rgb/1305031953.304968.png 1305031953.316977 depth/1305031953.316977.png
1305031953.337012 rgb/1305031953.337012.png 1305031953.347948 depth/1305031953.347948.png
1305031953.372964 rgb/1305031953.372964.png 1305031953.384173 depth/1305031953.384173.png
1305031953.404920 rgb/1305031953.404920.png 1305031953.415905 depth/1305031953.415905.png
1305031953.436876 rgb/1305031953.436876.png 1305031953.452336 depth/1305031953.452336.png
1305031953.473261 rgb/1305031953.473261.png 1305031953.483838 depth/1305031953.483838.png
1305031953.504919 rgb/1305031953.504919.png 1305031953.515920 depth/1305031953.515920.png
1305031953.536948 rgb/1305031953.536948.png 1305031953.551507 depth/1305031953.551507.png
1305031953.572862 rgb/1305031953.572862.png 1305031953.584439 depth/1305031953.584439.png
1305031953.604882 rgb/1305031953.604882.png 1305031953.618056 depth/1305031953.618056.png
1305031953.636962 rgb/1305031953.636962.png 1305031953.654177 depth/1305031953.654177.png
1305031953.673021 rgb/1305031953.673021.png 1305031953.683774 depth/1305031953.683774.png
1305031953.704929 rgb/1305031953.704929.png 1305031953.715952 depth/1305031953.715952.png
1305031953.736982 rgb/1305031953.736982.png 1305031953.752395 depth/1305031953.752395.png
1305031953.772886 rgb/1305031953.772886.png 1305031953.782908 depth/1305031953.782908.png
1305031953.804859 rgb/1305031953.804859.png 1305031953.816480 depth/1305031953.816480.png
1305031953.836840 rgb/1305031953.836840.png 1305031953.852417 depth/1305031953.852417.png
1305031953.872987 rgb/1305031953.872987.png 1305031953.884444 depth/1305031953.884444.png
1305031953.904912 rgb/1305031953.904912.png 1305031953.916154 depth/1305031953.916154.png
1305031953.936924 rgb/1305031953.936924.png 1305031953.952308 depth/1305031953.952308.png
1305031953.972857 rgb/1305031953.972857.png 1305031953.985028 depth/1305031953.985028.png
1305031954.004852 rgb/1305031954.004852.png 1305031954.017015 depth/1305031954.017015.png
1305031954.036921 rgb/1305031954.036921.png 1305031954.051816 depth/1305031954.051816.png
1305031954.072918 rgb/1305031954.072918.png 1305031954.085429 depth/1305031954.085429.png
1305031954.104933 rgb/1305031954.104933.png 1305031954.115779 depth/1305031954.115779.png
1305031954.136939 rgb/1305031954.136939.png 1305031954.152181 depth/1305031954.152181.png
1305031954.172997 rgb/1305031954.172997.png 1305031954.184964 depth/1305031954.184964.png
1305031954.204838 rgb/1305031954.204838.png 1305031954.217228 depth/1305031954.217228.png
1305031954.237023 rgb/1305031954.237023.png 1305031954.252057 depth/1305031954.252057.png
1305031954.272870 rgb/1305031954.272870.png 1305031954.285809 depth/1305031954.285809.png
1305031954.304869 rgb/1305031954.304869.png 1305031954.317325 depth/1305031954.317325.png
1305031954.336921 rgb/1305031954.336921.png 1305031954.348938 depth/1305031954.348938.png
1305031954.372872 rgb/1305031954.372872.png 1305031954.384479 depth/1305031954.384479.png
1305031954.404711 rgb/1305031954.404711.png 1305031954.416646 depth/1305031954.416646.png
1305031954.436896 rgb/1305031954.436896.png 1305031954.452249 depth/1305031954.452249.png
1305031954.472974 rgb/1305031954.472974.png 1305031954.483636 depth/1305031954.483636.png
1305031954.504827 rgb/1305031954.504827.png 1305031954.514991 depth/1305031954.514991.png
1305031954.536934 rgb/1305031954.536934.png 1305031954.552961 depth/1305031954.552961.png
1305031954.572946 rgb/1305031954.572946.png 1305031954.583506 depth/1305031954.583506.png
1305031954.604885 rgb/1305031954.604885.png 1305031954.616389 depth/1305031954.616389.png
1305031954.636862 rgb/1305031954.636862.png 1305031954.651711 depth/1305031954.651711.png
1305031954.672891 rgb/1305031954.672891.png 1305031954.683635 depth/1305031954.683635.png
1305031954.704892 rgb/1305031954.704892.png 1305031954.720557 depth/1305031954.720557.png
1305031954.736939 rgb/1305031954.736939.png 1305031954.751545 depth/1305031954.751545.png
1305031954.773183 rgb/1305031954.773183.png 1305031954.783603 depth/1305031954.783603.png
1305031954.804833 rgb/1305031954.804833.png 1305031954.820887 depth/1305031954.820887.png
1305031954.836924 rgb/1305031954.836924.png 1305031954.851912 depth/1305031954.851912.png
1305031954.873001 rgb/1305031954.873001.png 1305031954.883976 depth/1305031954.883976.png
1305031954.904866 rgb/1305031954.904866.png 1305031954.919388 depth/1305031954.919388.png
1305031954.937022 rgb/1305031954.937022.png 1305031954.951822 depth/1305031954.951822.png
1305031954.972931 rgb/1305031954.972931.png 1305031954.983417 depth/1305031954.983417.png
1305031955.004936 rgb/1305031955.004936.png 1305031955.019886 depth/1305031955.019886.png
1305031955.036969 rgb/1305031955.036969.png 1305031955.051198 depth/1305031955.051198.png
1305031955.073048 rgb/1305031955.073048.png 1305031955.083486 depth/1305031955.083486.png
1305031955.104929 rgb/1305031955.104929.png 1305031955.119530 depth/1305031955.119530.png
1305031955.136878 rgb/1305031955.136878.png 1305031955.150462 depth/1305031955.150462.png
1305031955.173003 rgb/1305031955.173003.png 1305031955.182670 depth/1305031955.182670.png
1305031955.204960 rgb/1305031955.204960.png 1305031955.219463 depth/1305031955.219463.png
1305031955.236857 rgb/1305031955.236857.png 1305031955.252519 depth/1305031955.252519.png
1305031955.272905 rgb/1305031955.272905.png 1305031955.283877 depth/1305031955.283877.png
1305031955.304880 rgb/1305031955.304880.png 1305031955.321200 depth/1305031955.321200.png
1305031955.337035 rgb/1305031955.337035.png 1305031955.350590 depth/1305031955.350590.png
1305031955.372861 rgb/1305031955.372861.png 1305031955.385074 depth/1305031955.385074.png
1305031955.404928 rgb/1305031955.404928.png 1305031955.418493 depth/1305031955.418493.png
1305031955.436909 rgb/1305031955.436909.png 1305031955.453866 depth/1305031955.453866.png
1305031955.472931 rgb/1305031955.472931.png 1305031955.484155 depth/1305031955.484155.png
1305031955.504893 rgb/1305031955.504893.png 1305031955.520645 depth/1305031955.520645.png
1305031955.536891 rgb/1305031955.536891.png 1305031955.552015 depth/1305031955.552015.png
1305031955.572893 rgb/1305031955.572893.png 1305031955.585017 depth/1305031955.585017.png
1305031955.604944 rgb/1305031955.604944.png 1305031955.621372 depth/1305031955.621372.png
1305031955.636881 rgb/1305031955.636881.png 1305031955.652029 depth/1305031955.652029.png
1305031955.672837 rgb/1305031955.672837.png 1305031955.685832 depth/1305031955.685832.png
1305031955.704890 rgb/1305031955.704890.png 1305031955.719498 depth/1305031955.719498.png
1305031955.736903 rgb/1305031955.736903.png 1305031955.751498 depth/1305031955.751498.png
1305031955.772963 rgb/1305031955.772963.png 1305031955.784581 depth/1305031955.784581.png
1305031955.804902 rgb/1305031955.804902.png 1305031955.820489 depth/1305031955.820489.png
1305031955.837019 rgb/1305031955.837019.png 1305031955.851625 depth/1305031955.851625.png
1305031955.872917 rgb/1305031955.872917.png 1305031955.887875 depth/1305031955.887875.png
1305031955.904911 rgb/1305031955.904911.png 1305031955.921521 depth/1305031955.921521.png
1305031955.937291 rgb/1305031955.937291.png 1305031955.951838 depth/1305031955.951838.png
1305031955.973194 rgb/1305031955.973194.png 1305031955.987663 depth/1305031955.987663.png
1305031956.004870 rgb/1305031956.004870.png 1305031956.020120 depth/1305031956.020120.png
1305031956.036937 rgb/1305031956.036937.png 1305031956.050008 depth/1305031956.050008.png
1305031956.073037 rgb/1305031956.073037.png 1305031956.087830 depth/1305031956.087830.png
1305031956.104901 rgb/1305031956.104901.png 1305031956.119493 depth/1305031956.119493.png
================================================
FILE: Examples/RGB-D/associations/fr1_xyz.txt
================================================
1305031102.175304 rgb/1305031102.175304.png 1305031102.160407 depth/1305031102.160407.png
1305031102.211214 rgb/1305031102.211214.png 1305031102.226738 depth/1305031102.226738.png
1305031102.275326 rgb/1305031102.275326.png 1305031102.262886 depth/1305031102.262886.png
1305031102.311267 rgb/1305031102.311267.png 1305031102.295279 depth/1305031102.295279.png
1305031102.343233 rgb/1305031102.343233.png 1305031102.329195 depth/1305031102.329195.png
1305031102.375329 rgb/1305031102.375329.png 1305031102.363013 depth/1305031102.363013.png
1305031102.411258 rgb/1305031102.411258.png 1305031102.394772 depth/1305031102.394772.png
1305031102.443271 rgb/1305031102.443271.png 1305031102.427815 depth/1305031102.427815.png
1305031102.475318 rgb/1305031102.475318.png 1305031102.462395 depth/1305031102.462395.png
1305031102.511219 rgb/1305031102.511219.png 1305031102.526330 depth/1305031102.526330.png
1305031102.575286 rgb/1305031102.575286.png 1305031102.562224 depth/1305031102.562224.png
1305031102.611233 rgb/1305031102.611233.png 1305031102.626818 depth/1305031102.626818.png
1305031102.675285 rgb/1305031102.675285.png 1305031102.663273 depth/1305031102.663273.png
1305031102.711263 rgb/1305031102.711263.png 1305031102.695165 depth/1305031102.695165.png
1305031102.743234 rgb/1305031102.743234.png 1305031102.728423 depth/1305031102.728423.png
1305031102.775472 rgb/1305031102.775472.png 1305031102.763549 depth/1305031102.763549.png
1305031102.811232 rgb/1305031102.811232.png 1305031102.794978 depth/1305031102.794978.png
1305031102.843290 rgb/1305031102.843290.png 1305031102.828537 depth/1305031102.828537.png
1305031102.875363 rgb/1305031102.875363.png 1305031102.862808 depth/1305031102.862808.png
1305031102.911185 rgb/1305031102.911185.png 1305031102.926851 depth/1305031102.926851.png
1305031102.975203 rgb/1305031102.975203.png 1305031102.962137 depth/1305031102.962137.png
1305031103.011215 rgb/1305031103.011215.png 1305031102.994164 depth/1305031102.994164.png
1305031103.043227 rgb/1305031103.043227.png 1305031103.027881 depth/1305031103.027881.png
1305031103.075319 rgb/1305031103.075319.png 1305031103.062273 depth/1305031103.062273.png
1305031103.111240 rgb/1305031103.111240.png 1305031103.094040 depth/1305031103.094040.png
1305031103.143318 rgb/1305031103.143318.png 1305031103.129109 depth/1305031103.129109.png
1305031103.175452 rgb/1305031103.175452.png 1305031103.162795 depth/1305031103.162795.png
1305031103.243216 rgb/1305031103.243216.png 1305031103.227845 depth/1305031103.227845.png
1305031103.275370 rgb/1305031103.275370.png 1305031103.262576 depth/1305031103.262576.png
1305031103.311210 rgb/1305031103.311210.png 1305031103.294208 depth/1305031103.294208.png
1305031103.343223 rgb/1305031103.343223.png 1305031103.327550 depth/1305031103.327550.png
1305031103.375327 rgb/1305031103.375327.png 1305031103.362405 depth/1305031103.362405.png
1305031103.411260 rgb/1305031103.411260.png 1305031103.394162 depth/1305031103.394162.png
1305031103.443280 rgb/1305031103.443280.png 1305031103.428437 depth/1305031103.428437.png
1305031103.475274 rgb/1305031103.475274.png 1305031103.463886 depth/1305031103.463886.png
1305031103.511333 rgb/1305031103.511333.png 1305031103.494472 depth/1305031103.494472.png
1305031103.543444 rgb/1305031103.543444.png 1305031103.531502 depth/1305031103.531502.png
1305031103.575474 rgb/1305031103.575474.png 1305031103.562651 depth/1305031103.562651.png
1305031103.611223 rgb/1305031103.611223.png 1305031103.595310 depth/1305031103.595310.png
1305031103.643445 rgb/1305031103.643445.png 1305031103.631376 depth/1305031103.631376.png
1305031103.675523 rgb/1305031103.675523.png 1305031103.663594 depth/1305031103.663594.png
1305031103.711610 rgb/1305031103.711610.png 1305031103.694695 depth/1305031103.694695.png
1305031103.743326 rgb/1305031103.743326.png 1305031103.731542 depth/1305031103.731542.png
1305031103.775342 rgb/1305031103.775342.png 1305031103.762865 depth/1305031103.762865.png
1305031103.811242 rgb/1305031103.811242.png 1305031103.794329 depth/1305031103.794329.png
1305031103.843251 rgb/1305031103.843251.png 1305031103.830367 depth/1305031103.830367.png
1305031103.875361 rgb/1305031103.875361.png 1305031103.862379 depth/1305031103.862379.png
1305031103.911221 rgb/1305031103.911221.png 1305031103.894237 depth/1305031103.894237.png
1305031103.943211 rgb/1305031103.943211.png 1305031103.930503 depth/1305031103.930503.png
1305031103.975373 rgb/1305031103.975373.png 1305031103.962461 depth/1305031103.962461.png
1305031104.011232 rgb/1305031104.011232.png 1305031103.994365 depth/1305031103.994365.png
1305031104.043249 rgb/1305031104.043249.png 1305031104.030279 depth/1305031104.030279.png
1305031104.075425 rgb/1305031104.075425.png 1305031104.062542 depth/1305031104.062542.png
1305031104.111235 rgb/1305031104.111235.png 1305031104.095305 depth/1305031104.095305.png
1305031104.143230 rgb/1305031104.143230.png 1305031104.131292 depth/1305031104.131292.png
1305031104.175424 rgb/1305031104.175424.png 1305031104.163440 depth/1305031104.163440.png
1305031104.211283 rgb/1305031104.211283.png 1305031104.194053 depth/1305031104.194053.png
1305031104.243196 rgb/1305031104.243196.png 1305031104.227247 depth/1305031104.227247.png
1305031104.275546 rgb/1305031104.275546.png 1305031104.263335 depth/1305031104.263335.png
1305031104.311219 rgb/1305031104.311219.png 1305031104.294957 depth/1305031104.294957.png
1305031104.343342 rgb/1305031104.343342.png 1305031104.331403 depth/1305031104.331403.png
1305031104.375837 rgb/1305031104.375837.png 1305031104.363345 depth/1305031104.363345.png
1305031104.411509 rgb/1305031104.411509.png 1305031104.395019 depth/1305031104.395019.png
1305031104.443288 rgb/1305031104.443288.png 1305031104.431435 depth/1305031104.431435.png
1305031104.475456 rgb/1305031104.475456.png 1305031104.463413 depth/1305031104.463413.png
1305031104.511329 rgb/1305031104.511329.png 1305031104.495673 depth/1305031104.495673.png
1305031104.543368 rgb/1305031104.543368.png 1305031104.531450 depth/1305031104.531450.png
1305031104.575343 rgb/1305031104.575343.png 1305031104.563149 depth/1305031104.563149.png
1305031104.611336 rgb/1305031104.611336.png 1305031104.595033 depth/1305031104.595033.png
1305031104.643243 rgb/1305031104.643243.png 1305031104.631368 depth/1305031104.631368.png
1305031104.675525 rgb/1305031104.675525.png 1305031104.659863 depth/1305031104.659863.png
1305031104.711277 rgb/1305031104.711277.png 1305031104.695185 depth/1305031104.695185.png
1305031104.743280 rgb/1305031104.743280.png 1305031104.730936 depth/1305031104.730936.png
1305031104.775327 rgb/1305031104.775327.png 1305031104.763178 depth/1305031104.763178.png
1305031104.811465 rgb/1305031104.811465.png 1305031104.799499 depth/1305031104.799499.png
1305031104.843258 rgb/1305031104.843258.png 1305031104.830961 depth/1305031104.830961.png
1305031104.875350 rgb/1305031104.875350.png 1305031104.863256 depth/1305031104.863256.png
1305031104.911534 rgb/1305031104.911534.png 1305031104.899165 depth/1305031104.899165.png
1305031104.943262 rgb/1305031104.943262.png 1305031104.931091 depth/1305031104.931091.png
1305031104.975202 rgb/1305031104.975202.png 1305031104.959750 depth/1305031104.959750.png
1305031105.011290 rgb/1305031105.011290.png 1305031104.998342 depth/1305031104.998342.png
1305031105.043373 rgb/1305031105.043373.png 1305031105.030427 depth/1305031105.030427.png
1305031105.075320 rgb/1305031105.075320.png 1305031105.062445 depth/1305031105.062445.png
1305031105.111299 rgb/1305031105.111299.png 1305031105.097639 depth/1305031105.097639.png
1305031105.143106 rgb/1305031105.143106.png 1305031105.130269 depth/1305031105.130269.png
1305031105.175159 rgb/1305031105.175159.png 1305031105.159979 depth/1305031105.159979.png
1305031105.211268 rgb/1305031105.211268.png 1305031105.198212 depth/1305031105.198212.png
1305031105.243270 rgb/1305031105.243270.png 1305031105.228250 depth/1305031105.228250.png
1305031105.275288 rgb/1305031105.275288.png 1305031105.262389 depth/1305031105.262389.png
1305031105.311290 rgb/1305031105.311290.png 1305031105.298501 depth/1305031105.298501.png
1305031105.343302 rgb/1305031105.343302.png 1305031105.328878 depth/1305031105.328878.png
1305031105.375338 rgb/1305031105.375338.png 1305031105.362286 depth/1305031105.362286.png
1305031105.411286 rgb/1305031105.411286.png 1305031105.398191 depth/1305031105.398191.png
1305031105.443316 rgb/1305031105.443316.png 1305031105.430336 depth/1305031105.430336.png
1305031105.475280 rgb/1305031105.475280.png 1305031105.461421 depth/1305031105.461421.png
1305031105.511332 rgb/1305031105.511332.png 1305031105.497931 depth/1305031105.497931.png
1305031105.543282 rgb/1305031105.543282.png 1305031105.529583 depth/1305031105.529583.png
1305031105.575449 rgb/1305031105.575449.png 1305031105.562109 depth/1305031105.562109.png
1305031105.611378 rgb/1305031105.611378.png 1305031105.597193 depth/1305031105.597193.png
1305031105.643273 rgb/1305031105.643273.png 1305031105.659104 depth/1305031105.659104.png
1305031105.711309 rgb/1305031105.711309.png 1305031105.698235 depth/1305031105.698235.png
1305031105.743312 rgb/1305031105.743312.png 1305031105.730336 depth/1305031105.730336.png
1305031105.775339 rgb/1305031105.775339.png 1305031105.762384 depth/1305031105.762384.png
1305031105.811283 rgb/1305031105.811283.png 1305031105.798056 depth/1305031105.798056.png
1305031105.843271 rgb/1305031105.843271.png 1305031105.830008 depth/1305031105.830008.png
1305031105.875337 rgb/1305031105.875337.png 1305031105.862238 depth/1305031105.862238.png
1305031105.911262 rgb/1305031105.911262.png 1305031105.898018 depth/1305031105.898018.png
1305031105.943272 rgb/1305031105.943272.png 1305031105.929855 depth/1305031105.929855.png
1305031105.975329 rgb/1305031105.975329.png 1305031105.966193 depth/1305031105.966193.png
1305031106.011285 rgb/1305031106.011285.png 1305031105.998271 depth/1305031105.998271.png
1305031106.043355 rgb/1305031106.043355.png 1305031106.030147 depth/1305031106.030147.png
1305031106.075330 rgb/1305031106.075330.png 1305031106.066060 depth/1305031106.066060.png
1305031106.111327 rgb/1305031106.111327.png 1305031106.096295 depth/1305031106.096295.png
1305031106.143355 rgb/1305031106.143355.png 1305031106.130445 depth/1305031106.130445.png
1305031106.175534 rgb/1305031106.175534.png 1305031106.166330 depth/1305031106.166330.png
1305031106.211275 rgb/1305031106.211275.png 1305031106.195074 depth/1305031106.195074.png
1305031106.243267 rgb/1305031106.243267.png 1305031106.230058 depth/1305031106.230058.png
1305031106.276385 rgb/1305031106.276385.png 1305031106.265976 depth/1305031106.265976.png
1305031106.311238 rgb/1305031106.311238.png 1305031106.298174 depth/1305031106.298174.png
1305031106.343258 rgb/1305031106.343258.png 1305031106.330215 depth/1305031106.330215.png
1305031106.375388 rgb/1305031106.375388.png 1305031106.366158 depth/1305031106.366158.png
1305031106.411320 rgb/1305031106.411320.png 1305031106.398281 depth/1305031106.398281.png
1305031106.443278 rgb/1305031106.443278.png 1305031106.430639 depth/1305031106.430639.png
1305031106.475345 rgb/1305031106.475345.png 1305031106.466046 depth/1305031106.466046.png
1305031106.511129 rgb/1305031106.511129.png 1305031106.498096 depth/1305031106.498096.png
1305031106.543302 rgb/1305031106.543302.png 1305031106.528267 depth/1305031106.528267.png
1305031106.575282 rgb/1305031106.575282.png 1305031106.564414 depth/1305031106.564414.png
1305031106.611151 rgb/1305031106.611151.png 1305031106.597879 depth/1305031106.597879.png
1305031106.643207 rgb/1305031106.643207.png 1305031106.630776 depth/1305031106.630776.png
1305031106.675279 rgb/1305031106.675279.png 1305031106.667282 depth/1305031106.667282.png
1305031106.711508 rgb/1305031106.711508.png 1305031106.699110 depth/1305031106.699110.png
1305031106.743341 rgb/1305031106.743341.png 1305031106.729550 depth/1305031106.729550.png
1305031106.775390 rgb/1305031106.775390.png 1305031106.767126 depth/1305031106.767126.png
1305031106.811289 rgb/1305031106.811289.png 1305031106.798309 depth/1305031106.798309.png
1305031106.843416 rgb/1305031106.843416.png 1305031106.830652 depth/1305031106.830652.png
1305031106.875905 rgb/1305031106.875905.png 1305031106.866893 depth/1305031106.866893.png
1305031106.911243 rgb/1305031106.911243.png 1305031106.897828 depth/1305031106.897828.png
1305031106.943439 rgb/1305031106.943439.png 1305031106.930797 depth/1305031106.930797.png
1305031106.975547 rgb/1305031106.975547.png 1305031106.967232 depth/1305031106.967232.png
1305031107.011576 rgb/1305031107.011576.png 1305031106.998876 depth/1305031106.998876.png
1305031107.043281 rgb/1305031107.043281.png 1305031107.030348 depth/1305031107.030348.png
1305031107.075432 rgb/1305031107.075432.png 1305031107.066405 depth/1305031107.066405.png
1305031107.111229 rgb/1305031107.111229.png 1305031107.098268 depth/1305031107.098268.png
1305031107.143260 rgb/1305031107.143260.png 1305031107.130308 depth/1305031107.130308.png
1305031107.175399 rgb/1305031107.175399.png 1305031107.165964 depth/1305031107.165964.png
1305031107.211358 rgb/1305031107.211358.png 1305031107.198208 depth/1305031107.198208.png
1305031107.243378 rgb/1305031107.243378.png 1305031107.235026 depth/1305031107.235026.png
1305031107.275398 rgb/1305031107.275398.png 1305031107.267071 depth/1305031107.267071.png
1305031107.311226 rgb/1305031107.311226.png 1305031107.299273 depth/1305031107.299273.png
1305031107.343509 rgb/1305031107.343509.png 1305031107.334800 depth/1305031107.334800.png
1305031107.375413 rgb/1305031107.375413.png 1305031107.367183 depth/1305031107.367183.png
1305031107.411271 rgb/1305031107.411271.png 1305031107.399345 depth/1305031107.399345.png
1305031107.443419 rgb/1305031107.443419.png 1305031107.434926 depth/1305031107.434926.png
1305031107.475377 rgb/1305031107.475377.png 1305031107.467141 depth/1305031107.467141.png
1305031107.511352 rgb/1305031107.511352.png 1305031107.498426 depth/1305031107.498426.png
1305031107.543605 rgb/1305031107.543605.png 1305031107.534830 depth/1305031107.534830.png
1305031107.575454 rgb/1305031107.575454.png 1305031107.567015 depth/1305031107.567015.png
1305031107.611271 rgb/1305031107.611271.png 1305031107.598904 depth/1305031107.598904.png
1305031107.643323 rgb/1305031107.643323.png 1305031107.634944 depth/1305031107.634944.png
1305031107.675568 rgb/1305031107.675568.png 1305031107.667179 depth/1305031107.667179.png
1305031107.711307 rgb/1305031107.711307.png 1305031107.699390 depth/1305031107.699390.png
1305031107.743538 rgb/1305031107.743538.png 1305031107.735041 depth/1305031107.735041.png
1305031107.775802 rgb/1305031107.775802.png 1305031107.767895 depth/1305031107.767895.png
1305031107.811596 rgb/1305031107.811596.png 1305031107.799544 depth/1305031107.799544.png
1305031107.843332 rgb/1305031107.843332.png 1305031107.835751 depth/1305031107.835751.png
1305031107.875358 rgb/1305031107.875358.png 1305031107.863505 depth/1305031107.863505.png
1305031107.911541 rgb/1305031107.911541.png 1305031107.899222 depth/1305031107.899222.png
1305031107.943122 rgb/1305031107.943122.png 1305031107.933609 depth/1305031107.933609.png
1305031107.975807 rgb/1305031107.975807.png 1305031107.964840 depth/1305031107.964840.png
1305031108.011320 rgb/1305031108.011320.png 1305031107.998469 depth/1305031107.998469.png
1305031108.043418 rgb/1305031108.043418.png 1305031108.034824 depth/1305031108.034824.png
1305031108.075352 rgb/1305031108.075352.png 1305031108.067271 depth/1305031108.067271.png
1305031108.111378 rgb/1305031108.111378.png 1305031108.099365 depth/1305031108.099365.png
1305031108.143334 rgb/1305031108.143334.png 1305031108.135281 depth/1305031108.135281.png
1305031108.176058 rgb/1305031108.176058.png 1305031108.167357 depth/1305031108.167357.png
1305031108.211475 rgb/1305031108.211475.png 1305031108.199225 depth/1305031108.199225.png
1305031108.243347 rgb/1305031108.243347.png 1305031108.235213 depth/1305031108.235213.png
1305031108.275358 rgb/1305031108.275358.png 1305031108.267660 depth/1305031108.267660.png
1305031108.311332 rgb/1305031108.311332.png 1305031108.299547 depth/1305031108.299547.png
1305031108.343278 rgb/1305031108.343278.png 1305031108.335019 depth/1305031108.335019.png
1305031108.375410 rgb/1305031108.375410.png 1305031108.367285 depth/1305031108.367285.png
1305031108.411361 rgb/1305031108.411361.png 1305031108.399284 depth/1305031108.399284.png
1305031108.443610 rgb/1305031108.443610.png 1305031108.435023 depth/1305031108.435023.png
1305031108.475471 rgb/1305031108.475471.png 1305031108.467680 depth/1305031108.467680.png
1305031108.511378 rgb/1305031108.511378.png 1305031108.503548 depth/1305031108.503548.png
1305031108.543737 rgb/1305031108.543737.png 1305031108.534811 depth/1305031108.534811.png
1305031108.575414 rgb/1305031108.575414.png 1305031108.567154 depth/1305031108.567154.png
1305031108.611407 rgb/1305031108.611407.png 1305031108.603547 depth/1305031108.603547.png
1305031108.643303 rgb/1305031108.643303.png 1305031108.634212 depth/1305031108.634212.png
1305031108.675375 rgb/1305031108.675375.png 1305031108.667189 depth/1305031108.667189.png
1305031108.711411 rgb/1305031108.711411.png 1305031108.703346 depth/1305031108.703346.png
1305031108.743502 rgb/1305031108.743502.png 1305031108.735052 depth/1305031108.735052.png
1305031108.775493 rgb/1305031108.775493.png 1305031108.767031 depth/1305031108.767031.png
1305031108.811244 rgb/1305031108.811244.png 1305031108.803370 depth/1305031108.803370.png
1305031108.843264 rgb/1305031108.843264.png 1305031108.835163 depth/1305031108.835163.png
1305031108.876515 rgb/1305031108.876515.png 1305031108.867534 depth/1305031108.867534.png
1305031108.911364 rgb/1305031108.911364.png 1305031108.903540 depth/1305031108.903540.png
1305031108.943243 rgb/1305031108.943243.png 1305031108.935116 depth/1305031108.935116.png
1305031108.975268 rgb/1305031108.975268.png 1305031108.967245 depth/1305031108.967245.png
1305031109.011269 rgb/1305031109.011269.png 1305031109.003064 depth/1305031109.003064.png
1305031109.043277 rgb/1305031109.043277.png 1305031109.034955 depth/1305031109.034955.png
1305031109.075410 rgb/1305031109.075410.png 1305031109.067091 depth/1305031109.067091.png
1305031109.111282 rgb/1305031109.111282.png 1305031109.103294 depth/1305031109.103294.png
1305031109.143334 rgb/1305031109.143334.png 1305031109.134968 depth/1305031109.134968.png
1305031109.175464 rgb/1305031109.175464.png 1305031109.165848 depth/1305031109.165848.png
1305031109.211379 rgb/1305031109.211379.png 1305031109.203388 depth/1305031109.203388.png
1305031109.243290 rgb/1305031109.243290.png 1305031109.234324 depth/1305031109.234324.png
1305031109.275308 rgb/1305031109.275308.png 1305031109.266325 depth/1305031109.266325.png
1305031109.311329 rgb/1305031109.311329.png 1305031109.303457 depth/1305031109.303457.png
1305031109.343248 rgb/1305031109.343248.png 1305031109.334602 depth/1305031109.334602.png
1305031109.375397 rgb/1305031109.375397.png 1305031109.364882 depth/1305031109.364882.png
1305031109.411329 rgb/1305031109.411329.png 1305031109.403386 depth/1305031109.403386.png
1305031109.443302 rgb/1305031109.443302.png 1305031109.434469 depth/1305031109.434469.png
1305031109.475363 rgb/1305031109.475363.png 1305031109.467362 depth/1305031109.467362.png
1305031109.511273 rgb/1305031109.511273.png 1305031109.503193 depth/1305031109.503193.png
1305031109.543294 rgb/1305031109.543294.png 1305031109.535715 depth/1305031109.535715.png
1305031109.575362 rgb/1305031109.575362.png 1305031109.567452 depth/1305031109.567452.png
1305031109.611310 rgb/1305031109.611310.png 1305031109.603601 depth/1305031109.603601.png
1305031109.643229 rgb/1305031109.643229.png 1305031109.635323 depth/1305031109.635323.png
1305031109.675263 rgb/1305031109.675263.png 1305031109.667570 depth/1305031109.667570.png
1305031109.711312 rgb/1305031109.711312.png 1305031109.703265 depth/1305031109.703265.png
1305031109.743274 rgb/1305031109.743274.png 1305031109.735059 depth/1305031109.735059.png
1305031109.775277 rgb/1305031109.775277.png 1305031109.767470 depth/1305031109.767470.png
1305031109.811371 rgb/1305031109.811371.png 1305031109.803396 depth/1305031109.803396.png
1305031109.843296 rgb/1305031109.843296.png 1305031109.834910 depth/1305031109.834910.png
1305031109.875306 rgb/1305031109.875306.png 1305031109.871271 depth/1305031109.871271.png
1305031109.911265 rgb/1305031109.911265.png 1305031109.900535 depth/1305031109.900535.png
1305031109.943299 rgb/1305031109.943299.png 1305031109.934960 depth/1305031109.934960.png
1305031109.975258 rgb/1305031109.975258.png 1305031109.970213 depth/1305031109.970213.png
1305031110.011256 rgb/1305031110.011256.png 1305031109.999657 depth/1305031109.999657.png
1305031110.043299 rgb/1305031110.043299.png 1305031110.031356 depth/1305031110.031356.png
1305031110.075319 rgb/1305031110.075319.png 1305031110.068125 depth/1305031110.068125.png
1305031110.111325 rgb/1305031110.111325.png 1305031110.101397 depth/1305031110.101397.png
1305031110.143432 rgb/1305031110.143432.png 1305031110.132317 depth/1305031110.132317.png
1305031110.175641 rgb/1305031110.175641.png 1305031110.168323 depth/1305031110.168323.png
1305031110.211637 rgb/1305031110.211637.png 1305031110.203162 depth/1305031110.203162.png
1305031110.243323 rgb/1305031110.243323.png 1305031110.234909 depth/1305031110.234909.png
1305031110.279321 rgb/1305031110.279321.png 1305031110.271394 depth/1305031110.271394.png
1305031110.311404 rgb/1305031110.311404.png 1305031110.303648 depth/1305031110.303648.png
1305031110.343355 rgb/1305031110.343355.png 1305031110.331570 depth/1305031110.331570.png
1305031110.379281 rgb/1305031110.379281.png 1305031110.371607 depth/1305031110.371607.png
1305031110.411469 rgb/1305031110.411469.png 1305031110.403480 depth/1305031110.403480.png
1305031110.443260 rgb/1305031110.443260.png 1305031110.435647 depth/1305031110.435647.png
1305031110.479331 rgb/1305031110.479331.png 1305031110.470588 depth/1305031110.470588.png
1305031110.511429 rgb/1305031110.511429.png 1305031110.502539 depth/1305031110.502539.png
1305031110.543408 rgb/1305031110.543408.png 1305031110.534532 depth/1305031110.534532.png
1305031110.579426 rgb/1305031110.579426.png 1305031110.571676 depth/1305031110.571676.png
1305031110.611307 rgb/1305031110.611307.png 1305031110.604289 depth/1305031110.604289.png
1305031110.643418 rgb/1305031110.643418.png 1305031110.635485 depth/1305031110.635485.png
1305031110.679606 rgb/1305031110.679606.png 1305031110.671775 depth/1305031110.671775.png
1305031110.711412 rgb/1305031110.711412.png 1305031110.699957 depth/1305031110.699957.png
1305031110.743249 rgb/1305031110.743249.png 1305031110.735440 depth/1305031110.735440.png
1305031110.779193 rgb/1305031110.779193.png 1305031110.769734 depth/1305031110.769734.png
1305031110.811386 rgb/1305031110.811386.png 1305031110.799684 depth/1305031110.799684.png
1305031110.843218 rgb/1305031110.843218.png 1305031110.835248 depth/1305031110.835248.png
1305031110.879313 rgb/1305031110.879313.png 1305031110.871293 depth/1305031110.871293.png
1305031110.911333 rgb/1305031110.911333.png 1305031110.901900 depth/1305031110.901900.png
1305031110.943862 rgb/1305031110.943862.png 1305031110.938668 depth/1305031110.938668.png
1305031110.979345 rgb/1305031110.979345.png 1305031110.971316 depth/1305031110.971316.png
1305031111.011431 rgb/1305031111.011431.png 1305031111.003669 depth/1305031111.003669.png
1305031111.043327 rgb/1305031111.043327.png 1305031111.039669 depth/1305031111.039669.png
1305031111.079283 rgb/1305031111.079283.png 1305031111.071605 depth/1305031111.071605.png
1305031111.111508 rgb/1305031111.111508.png 1305031111.103658 depth/1305031111.103658.png
1305031111.143257 rgb/1305031111.143257.png 1305031111.139211 depth/1305031111.139211.png
1305031111.179326 rgb/1305031111.179326.png 1305031111.170937 depth/1305031111.170937.png
1305031111.211433 rgb/1305031111.211433.png 1305031111.199395 depth/1305031111.199395.png
1305031111.243236 rgb/1305031111.243236.png 1305031111.236670 depth/1305031111.236670.png
1305031111.279308 rgb/1305031111.279308.png 1305031111.269939 depth/1305031111.269939.png
1305031111.311547 rgb/1305031111.311547.png 1305031111.302311 depth/1305031111.302311.png
1305031111.343397 rgb/1305031111.343397.png 1305031111.339460 depth/1305031111.339460.png
1305031111.379134 rgb/1305031111.379134.png 1305031111.370908 depth/1305031111.370908.png
1305031111.411296 rgb/1305031111.411296.png 1305031111.402911 depth/1305031111.402911.png
1305031111.443386 rgb/1305031111.443386.png 1305031111.438948 depth/1305031111.438948.png
1305031111.479259 rgb/1305031111.479259.png 1305031111.470919 depth/1305031111.470919.png
1305031111.511264 rgb/1305031111.511264.png 1305031111.503531 depth/1305031111.503531.png
1305031111.543250 rgb/1305031111.543250.png 1305031111.539482 depth/1305031111.539482.png
1305031111.579237 rgb/1305031111.579237.png 1305031111.571320 depth/1305031111.571320.png
1305031111.611271 rgb/1305031111.611271.png 1305031111.603391 depth/1305031111.603391.png
1305031111.643395 rgb/1305031111.643395.png 1305031111.639405 depth/1305031111.639405.png
1305031111.679320 rgb/1305031111.679320.png 1305031111.671252 depth/1305031111.671252.png
1305031111.711760 rgb/1305031111.711760.png 1305031111.703791 depth/1305031111.703791.png
1305031111.743386 rgb/1305031111.743386.png 1305031111.739504 depth/1305031111.739504.png
1305031111.779423 rgb/1305031111.779423.png 1305031111.771228 depth/1305031111.771228.png
1305031111.811406 rgb/1305031111.811406.png 1305031111.800077 depth/1305031111.800077.png
1305031111.843299 rgb/1305031111.843299.png 1305031111.839333 depth/1305031111.839333.png
1305031111.879442 rgb/1305031111.879442.png 1305031111.870985 depth/1305031111.870985.png
1305031111.911354 rgb/1305031111.911354.png 1305031111.903356 depth/1305031111.903356.png
1305031111.943300 rgb/1305031111.943300.png 1305031111.939680 depth/1305031111.939680.png
1305031111.979449 rgb/1305031111.979449.png 1305031111.971494 depth/1305031111.971494.png
1305031112.011433 rgb/1305031112.011433.png 1305031112.003596 depth/1305031112.003596.png
1305031112.043270 rgb/1305031112.043270.png 1305031112.039412 depth/1305031112.039412.png
1305031112.079339 rgb/1305031112.079339.png 1305031112.070731 depth/1305031112.070731.png
1305031112.111423 rgb/1305031112.111423.png 1305031112.102495 depth/1305031112.102495.png
1305031112.144342 rgb/1305031112.144342.png 1305031112.139107 depth/1305031112.139107.png
1305031112.179390 rgb/1305031112.179390.png 1305031112.169345 depth/1305031112.169345.png
1305031112.211254 rgb/1305031112.211254.png 1305031112.207733 depth/1305031112.207733.png
1305031112.243369 rgb/1305031112.243369.png 1305031112.235657 depth/1305031112.235657.png
1305031112.279353 rgb/1305031112.279353.png 1305031112.269488 depth/1305031112.269488.png
1305031112.311312 rgb/1305031112.311312.png 1305031112.303591 depth/1305031112.303591.png
1305031112.343323 rgb/1305031112.343323.png 1305031112.335789 depth/1305031112.335789.png
1305031112.379360 rgb/1305031112.379360.png 1305031112.371231 depth/1305031112.371231.png
1305031112.411442 rgb/1305031112.411442.png 1305031112.407491 depth/1305031112.407491.png
1305031112.443391 rgb/1305031112.443391.png 1305031112.439064 depth/1305031112.439064.png
1305031112.479418 rgb/1305031112.479418.png 1305031112.471066 depth/1305031112.471066.png
1305031112.511504 rgb/1305031112.511504.png 1305031112.506669 depth/1305031112.506669.png
1305031112.543212 rgb/1305031112.543212.png 1305031112.538310 depth/1305031112.538310.png
1305031112.579252 rgb/1305031112.579252.png 1305031112.567470 depth/1305031112.567470.png
1305031112.611261 rgb/1305031112.611261.png 1305031112.606742 depth/1305031112.606742.png
1305031112.643246 rgb/1305031112.643246.png 1305031112.639418 depth/1305031112.639418.png
1305031112.679952 rgb/1305031112.679952.png 1305031112.671325 depth/1305031112.671325.png
1305031112.711251 rgb/1305031112.711251.png 1305031112.707325 depth/1305031112.707325.png
1305031112.743245 rgb/1305031112.743245.png 1305031112.739546 depth/1305031112.739546.png
1305031112.779310 rgb/1305031112.779310.png 1305031112.771523 depth/1305031112.771523.png
1305031112.811310 rgb/1305031112.811310.png 1305031112.807539 depth/1305031112.807539.png
1305031112.843286 rgb/1305031112.843286.png 1305031112.839560 depth/1305031112.839560.png
1305031112.879421 rgb/1305031112.879421.png 1305031112.871083 depth/1305031112.871083.png
1305031112.911411 rgb/1305031112.911411.png 1305031112.907246 depth/1305031112.907246.png
1305031112.943321 rgb/1305031112.943321.png 1305031112.939323 depth/1305031112.939323.png
1305031112.979278 rgb/1305031112.979278.png 1305031112.971164 depth/1305031112.971164.png
1305031113.011353 rgb/1305031113.011353.png 1305031113.007166 depth/1305031113.007166.png
1305031113.043231 rgb/1305031113.043231.png 1305031113.039492 depth/1305031113.039492.png
1305031113.079251 rgb/1305031113.079251.png 1305031113.071210 depth/1305031113.071210.png
1305031113.111316 rgb/1305031113.111316.png 1305031113.107662 depth/1305031113.107662.png
1305031113.143306 rgb/1305031113.143306.png 1305031113.139664 depth/1305031113.139664.png
1305031113.179343 rgb/1305031113.179343.png 1305031113.171088 depth/1305031113.171088.png
1305031113.211259 rgb/1305031113.211259.png 1305031113.207181 depth/1305031113.207181.png
1305031113.243227 rgb/1305031113.243227.png 1305031113.239732 depth/1305031113.239732.png
1305031113.279312 rgb/1305031113.279312.png 1305031113.271470 depth/1305031113.271470.png
1305031113.311452 rgb/1305031113.311452.png 1305031113.307323 depth/1305031113.307323.png
1305031113.343252 rgb/1305031113.343252.png 1305031113.339396 depth/1305031113.339396.png
1305031113.379312 rgb/1305031113.379312.png 1305031113.371377 depth/1305031113.371377.png
1305031113.411625 rgb/1305031113.411625.png 1305031113.407351 depth/1305031113.407351.png
1305031113.443266 rgb/1305031113.443266.png 1305031113.439787 depth/1305031113.439787.png
1305031113.479311 rgb/1305031113.479311.png 1305031113.475657 depth/1305031113.475657.png
1305031113.511523 rgb/1305031113.511523.png 1305031113.507987 depth/1305031113.507987.png
1305031113.543242 rgb/1305031113.543242.png 1305031113.539417 depth/1305031113.539417.png
1305031113.579301 rgb/1305031113.579301.png 1305031113.574964 depth/1305031113.574964.png
1305031113.611268 rgb/1305031113.611268.png 1305031113.607216 depth/1305031113.607216.png
1305031113.643222 rgb/1305031113.643222.png 1305031113.638418 depth/1305031113.638418.png
1305031113.679288 rgb/1305031113.679288.png 1305031113.674244 depth/1305031113.674244.png
1305031113.711931 rgb/1305031113.711931.png 1305031113.704256 depth/1305031113.704256.png
1305031113.743590 rgb/1305031113.743590.png 1305031113.736263 depth/1305031113.736263.png
1305031113.779320 rgb/1305031113.779320.png 1305031113.774168 depth/1305031113.774168.png
1305031113.811237 rgb/1305031113.811237.png 1305031113.805795 depth/1305031113.805795.png
1305031113.843295 rgb/1305031113.843295.png 1305031113.838437 depth/1305031113.838437.png
1305031113.879281 rgb/1305031113.879281.png 1305031113.874200 depth/1305031113.874200.png
1305031113.911290 rgb/1305031113.911290.png 1305031113.906361 depth/1305031113.906361.png
1305031113.943291 rgb/1305031113.943291.png 1305031113.938561 depth/1305031113.938561.png
1305031113.979293 rgb/1305031113.979293.png 1305031113.974245 depth/1305031113.974245.png
1305031114.011257 rgb/1305031114.011257.png 1305031114.007082 depth/1305031114.007082.png
1305031114.043301 rgb/1305031114.043301.png 1305031114.038546 depth/1305031114.038546.png
1305031114.079285 rgb/1305031114.079285.png 1305031114.074298 depth/1305031114.074298.png
1305031114.111263 rgb/1305031114.111263.png 1305031114.106402 depth/1305031114.106402.png
1305031114.143284 rgb/1305031114.143284.png 1305031114.138562 depth/1305031114.138562.png
1305031114.179337 rgb/1305031114.179337.png 1305031114.174114 depth/1305031114.174114.png
1305031114.211303 rgb/1305031114.211303.png 1305031114.206255 depth/1305031114.206255.png
1305031114.243337 rgb/1305031114.243337.png 1305031114.238473 depth/1305031114.238473.png
1305031114.279390 rgb/1305031114.279390.png 1305031114.271075 depth/1305031114.271075.png
1305031114.311429 rgb/1305031114.311429.png 1305031114.306710 depth/1305031114.306710.png
1305031114.343331 rgb/1305031114.343331.png 1305031114.338919 depth/1305031114.338919.png
1305031114.379320 rgb/1305031114.379320.png 1305031114.374307 depth/1305031114.374307.png
1305031114.411397 rgb/1305031114.411397.png 1305031114.406591 depth/1305031114.406591.png
1305031114.443345 rgb/1305031114.443345.png 1305031114.438540 depth/1305031114.438540.png
1305031114.479332 rgb/1305031114.479332.png 1305031114.474489 depth/1305031114.474489.png
1305031114.511266 rgb/1305031114.511266.png 1305031114.506573 depth/1305031114.506573.png
1305031114.543236 rgb/1305031114.543236.png 1305031114.539953 depth/1305031114.539953.png
1305031114.579237 rgb/1305031114.579237.png 1305031114.575185 depth/1305031114.575185.png
1305031114.611391 rgb/1305031114.611391.png 1305031114.607560 depth/1305031114.607560.png
1305031114.644136 rgb/1305031114.644136.png 1305031114.644150 depth/1305031114.644150.png
1305031114.679251 rgb/1305031114.679251.png 1305031114.675655 depth/1305031114.675655.png
1305031114.711306 rgb/1305031114.711306.png 1305031114.706141 depth/1305031114.706141.png
1305031114.743200 rgb/1305031114.743200.png 1305031114.743276 depth/1305031114.743276.png
1305031114.779289 rgb/1305031114.779289.png 1305031114.774847 depth/1305031114.774847.png
1305031114.811303 rgb/1305031114.811303.png 1305031114.807310 depth/1305031114.807310.png
1305031114.843208 rgb/1305031114.843208.png 1305031114.842137 depth/1305031114.842137.png
1305031114.879281 rgb/1305031114.879281.png 1305031114.875056 depth/1305031114.875056.png
1305031114.912879 rgb/1305031114.912879.png 1305031114.907504 depth/1305031114.907504.png
1305031114.943234 rgb/1305031114.943234.png 1305031114.943264 depth/1305031114.943264.png
1305031114.979280 rgb/1305031114.979280.png 1305031114.975411 depth/1305031114.975411.png
1305031115.011300 rgb/1305031115.011300.png 1305031115.007179 depth/1305031115.007179.png
1305031115.043508 rgb/1305031115.043508.png 1305031115.043530 depth/1305031115.043530.png
1305031115.079238 rgb/1305031115.079238.png 1305031115.071577 depth/1305031115.071577.png
1305031115.111230 rgb/1305031115.111230.png 1305031115.107074 depth/1305031115.107074.png
1305031115.143275 rgb/1305031115.143275.png 1305031115.143294 depth/1305031115.143294.png
1305031115.179440 rgb/1305031115.179440.png 1305031115.172642 depth/1305031115.172642.png
1305031115.211374 rgb/1305031115.211374.png 1305031115.206453 depth/1305031115.206453.png
1305031115.243297 rgb/1305031115.243297.png 1305031115.240975 depth/1305031115.240975.png
1305031115.279966 rgb/1305031115.279966.png 1305031115.273468 depth/1305031115.273468.png
1305031115.311704 rgb/1305031115.311704.png 1305031115.305534 depth/1305031115.305534.png
1305031115.343235 rgb/1305031115.343235.png 1305031115.343426 depth/1305031115.343426.png
1305031115.379166 rgb/1305031115.379166.png 1305031115.375054 depth/1305031115.375054.png
1305031115.411237 rgb/1305031115.411237.png 1305031115.406164 depth/1305031115.406164.png
1305031115.443159 rgb/1305031115.443159.png 1305031115.443040 depth/1305031115.443040.png
1305031115.479241 rgb/1305031115.479241.png 1305031115.474863 depth/1305031115.474863.png
1305031115.511253 rgb/1305031115.511253.png 1305031115.507440 depth/1305031115.507440.png
1305031115.543604 rgb/1305031115.543604.png 1305031115.543620 depth/1305031115.543620.png
1305031115.579315 rgb/1305031115.579315.png 1305031115.575290 depth/1305031115.575290.png
1305031115.611424 rgb/1305031115.611424.png 1305031115.607428 depth/1305031115.607428.png
1305031115.643254 rgb/1305031115.643254.png 1305031115.643254 depth/1305031115.643254.png
1305031115.679241 rgb/1305031115.679241.png 1305031115.675106 depth/1305031115.675106.png
1305031115.711320 rgb/1305031115.711320.png 1305031115.706301 depth/1305031115.706301.png
1305031115.743250 rgb/1305031115.743250.png 1305031115.742905 depth/1305031115.742905.png
1305031115.779425 rgb/1305031115.779425.png 1305031115.774329 depth/1305031115.774329.png
1305031115.811277 rgb/1305031115.811277.png 1305031115.806425 depth/1305031115.806425.png
1305031115.843224 rgb/1305031115.843224.png 1305031115.841936 depth/1305031115.841936.png
1305031115.879198 rgb/1305031115.879198.png 1305031115.875347 depth/1305031115.875347.png
1305031115.911118 rgb/1305031115.911118.png 1305031115.910716 depth/1305031115.910716.png
1305031115.943311 rgb/1305031115.943311.png 1305031115.942015 depth/1305031115.942015.png
1305031115.980740 rgb/1305031115.980740.png 1305031115.973799 depth/1305031115.973799.png
1305031116.011379 rgb/1305031116.011379.png 1305031116.010843 depth/1305031116.010843.png
1305031116.043164 rgb/1305031116.043164.png 1305031116.042618 depth/1305031116.042618.png
1305031116.080030 rgb/1305031116.080030.png 1305031116.071527 depth/1305031116.071527.png
1305031116.111300 rgb/1305031116.111300.png 1305031116.108247 depth/1305031116.108247.png
1305031116.143441 rgb/1305031116.143441.png 1305031116.143447 depth/1305031116.143447.png
1305031116.179572 rgb/1305031116.179572.png 1305031116.174891 depth/1305031116.174891.png
1305031116.211299 rgb/1305031116.211299.png 1305031116.211320 depth/1305031116.211320.png
1305031116.243320 rgb/1305031116.243320.png 1305031116.242720 depth/1305031116.242720.png
1305031116.279385 rgb/1305031116.279385.png 1305031116.274421 depth/1305031116.274421.png
1305031116.311336 rgb/1305031116.311336.png 1305031116.310686 depth/1305031116.310686.png
1305031116.343292 rgb/1305031116.343292.png 1305031116.342459 depth/1305031116.342459.png
1305031116.379384 rgb/1305031116.379384.png 1305031116.374490 depth/1305031116.374490.png
1305031116.411333 rgb/1305031116.411333.png 1305031116.409631 depth/1305031116.409631.png
1305031116.443369 rgb/1305031116.443369.png 1305031116.442496 depth/1305031116.442496.png
1305031116.479850 rgb/1305031116.479850.png 1305031116.473394 depth/1305031116.473394.png
1305031116.511205 rgb/1305031116.511205.png 1305031116.510576 depth/1305031116.510576.png
1305031116.543262 rgb/1305031116.543262.png 1305031116.542695 depth/1305031116.542695.png
1305031116.579313 rgb/1305031116.579313.png 1305031116.574389 depth/1305031116.574389.png
1305031116.611261 rgb/1305031116.611261.png 1305031116.610891 depth/1305031116.610891.png
1305031116.643355 rgb/1305031116.643355.png 1305031116.642664 depth/1305031116.642664.png
1305031116.679281 rgb/1305031116.679281.png 1305031116.674523 depth/1305031116.674523.png
1305031116.711634 rgb/1305031116.711634.png 1305031116.710942 depth/1305031116.710942.png
1305031116.743291 rgb/1305031116.743291.png 1305031116.740575 depth/1305031116.740575.png
1305031116.779298 rgb/1305031116.779298.png 1305031116.775059 depth/1305031116.775059.png
1305031116.811318 rgb/1305031116.811318.png 1305031116.811343 depth/1305031116.811343.png
1305031116.846089 rgb/1305031116.846089.png 1305031116.840370 depth/1305031116.840370.png
1305031116.880165 rgb/1305031116.880165.png 1305031116.871726 depth/1305031116.871726.png
1305031116.912044 rgb/1305031116.912044.png 1305031116.907955 depth/1305031116.907955.png
1305031116.943296 rgb/1305031116.943296.png 1305031116.940626 depth/1305031116.940626.png
1305031116.979351 rgb/1305031116.979351.png 1305031116.974656 depth/1305031116.974656.png
1305031117.011382 rgb/1305031117.011382.png 1305031117.008812 depth/1305031117.008812.png
1305031117.043261 rgb/1305031117.043261.png 1305031117.042065 depth/1305031117.042065.png
1305031117.079520 rgb/1305031117.079520.png 1305031117.071181 depth/1305031117.071181.png
1305031117.111238 rgb/1305031117.111238.png 1305031117.110454 depth/1305031117.110454.png
1305031117.143218 rgb/1305031117.143218.png 1305031117.142383 depth/1305031117.142383.png
1305031117.179264 rgb/1305031117.179264.png 1305031117.175059 depth/1305031117.175059.png
1305031117.211361 rgb/1305031117.211361.png 1305031117.207753 depth/1305031117.207753.png
1305031117.243277 rgb/1305031117.243277.png 1305031117.241340 depth/1305031117.241340.png
1305031117.279299 rgb/1305031117.279299.png 1305031117.276516 depth/1305031117.276516.png
1305031117.311200 rgb/1305031117.311200.png 1305031117.310121 depth/1305031117.310121.png
1305031117.343243 rgb/1305031117.343243.png 1305031117.341044 depth/1305031117.341044.png
1305031117.379454 rgb/1305031117.379454.png 1305031117.375067 depth/1305031117.375067.png
1305031117.411221 rgb/1305031117.411221.png 1305031117.408538 depth/1305031117.408538.png
1305031117.443274 rgb/1305031117.443274.png 1305031117.442208 depth/1305031117.442208.png
1305031117.479403 rgb/1305031117.479403.png 1305031117.475651 depth/1305031117.475651.png
1305031117.511325 rgb/1305031117.511325.png 1305031117.508882 depth/1305031117.508882.png
1305031117.544285 rgb/1305031117.544285.png 1305031117.539736 depth/1305031117.539736.png
1305031117.579155 rgb/1305031117.579155.png 1305031117.577860 depth/1305031117.577860.png
1305031117.611159 rgb/1305031117.611159.png 1305031117.607777 depth/1305031117.607777.png
1305031117.643252 rgb/1305031117.643252.png 1305031117.643284 depth/1305031117.643284.png
1305031117.679262 rgb/1305031117.679262.png 1305031117.675483 depth/1305031117.675483.png
1305031117.711184 rgb/1305031117.711184.png 1305031117.711215 depth/1305031117.711215.png
1305031117.743184 rgb/1305031117.743184.png 1305031117.742995 depth/1305031117.742995.png
1305031117.779467 rgb/1305031117.779467.png 1305031117.778969 depth/1305031117.778969.png
1305031117.811320 rgb/1305031117.811320.png 1305031117.811060 depth/1305031117.811060.png
1305031117.843291 rgb/1305031117.843291.png 1305031117.843307 depth/1305031117.843307.png
1305031117.879451 rgb/1305031117.879451.png 1305031117.879467 depth/1305031117.879467.png
1305031117.911407 rgb/1305031117.911407.png 1305031117.908762 depth/1305031117.908762.png
1305031117.943253 rgb/1305031117.943253.png 1305031117.943272 depth/1305031117.943272.png
1305031117.979228 rgb/1305031117.979228.png 1305031117.979263 depth/1305031117.979263.png
1305031118.011228 rgb/1305031118.011228.png 1305031118.011013 depth/1305031118.011013.png
1305031118.043521 rgb/1305031118.043521.png 1305031118.043549 depth/1305031118.043549.png
1305031118.079334 rgb/1305031118.079334.png 1305031118.079369 depth/1305031118.079369.png
1305031118.111217 rgb/1305031118.111217.png 1305031118.110863 depth/1305031118.110863.png
1305031118.143256 rgb/1305031118.143256.png 1305031118.142285 depth/1305031118.142285.png
1305031118.179323 rgb/1305031118.179323.png 1305031118.178170 depth/1305031118.178170.png
1305031118.211202 rgb/1305031118.211202.png 1305031118.210782 depth/1305031118.210782.png
1305031118.243173 rgb/1305031118.243173.png 1305031118.242948 depth/1305031118.242948.png
1305031118.279194 rgb/1305031118.279194.png 1305031118.278991 depth/1305031118.278991.png
1305031118.311299 rgb/1305031118.311299.png 1305031118.310731 depth/1305031118.310731.png
1305031118.343324 rgb/1305031118.343324.png 1305031118.342079 depth/1305031118.342079.png
1305031118.379208 rgb/1305031118.379208.png 1305031118.377003 depth/1305031118.377003.png
1305031118.411296 rgb/1305031118.411296.png 1305031118.408818 depth/1305031118.408818.png
1305031118.445692 rgb/1305031118.445692.png 1305031118.445703 depth/1305031118.445703.png
1305031118.479285 rgb/1305031118.479285.png 1305031118.477869 depth/1305031118.477869.png
1305031118.511255 rgb/1305031118.511255.png 1305031118.510201 depth/1305031118.510201.png
1305031118.544414 rgb/1305031118.544414.png 1305031118.545199 depth/1305031118.545199.png
1305031118.579285 rgb/1305031118.579285.png 1305031118.576377 depth/1305031118.576377.png
1305031118.616142 rgb/1305031118.616142.png 1305031118.610869 depth/1305031118.610869.png
1305031118.645325 rgb/1305031118.645325.png 1305031118.645331 depth/1305031118.645331.png
1305031118.679295 rgb/1305031118.679295.png 1305031118.675082 depth/1305031118.675082.png
1305031118.711421 rgb/1305031118.711421.png 1305031118.710140 depth/1305031118.710140.png
1305031118.746770 rgb/1305031118.746770.png 1305031118.746801 depth/1305031118.746801.png
1305031118.779277 rgb/1305031118.779277.png 1305031118.778790 depth/1305031118.778790.png
1305031118.811221 rgb/1305031118.811221.png 1305031118.810703 depth/1305031118.810703.png
1305031118.846753 rgb/1305031118.846753.png 1305031118.846774 depth/1305031118.846774.png
1305031118.879208 rgb/1305031118.879208.png 1305031118.875402 depth/1305031118.875402.png
1305031118.911177 rgb/1305031118.911177.png 1305031118.909608 depth/1305031118.909608.png
1305031118.946974 rgb/1305031118.946974.png 1305031118.947009 depth/1305031118.947009.png
1305031118.979374 rgb/1305031118.979374.png 1305031118.979394 depth/1305031118.979394.png
1305031119.011363 rgb/1305031119.011363.png 1305031119.009712 depth/1305031119.009712.png
1305031119.047172 rgb/1305031119.047172.png 1305031119.047180 depth/1305031119.047180.png
1305031119.079223 rgb/1305031119.079223.png 1305031119.078966 depth/1305031119.078966.png
1305031119.111328 rgb/1305031119.111328.png 1305031119.110884 depth/1305031119.110884.png
1305031119.147616 rgb/1305031119.147616.png 1305031119.147629 depth/1305031119.147629.png
1305031119.179226 rgb/1305031119.179226.png 1305031119.179262 depth/1305031119.179262.png
1305031119.211364 rgb/1305031119.211364.png 1305031119.210906 depth/1305031119.210906.png
1305031119.247399 rgb/1305031119.247399.png 1305031119.247660 depth/1305031119.247660.png
1305031119.279212 rgb/1305031119.279212.png 1305031119.279244 depth/1305031119.279244.png
1305031119.311212 rgb/1305031119.311212.png 1305031119.310755 depth/1305031119.310755.png
1305031119.347741 rgb/1305031119.347741.png 1305031119.347750 depth/1305031119.347750.png
1305031119.379239 rgb/1305031119.379239.png 1305031119.378631 depth/1305031119.378631.png
1305031119.411484 rgb/1305031119.411484.png 1305031119.411492 depth/1305031119.411492.png
1305031119.447706 rgb/1305031119.447706.png 1305031119.447726 depth/1305031119.447726.png
1305031119.479267 rgb/1305031119.479267.png 1305031119.477682 depth/1305031119.477682.png
1305031119.511240 rgb/1305031119.511240.png 1305031119.511258 depth/1305031119.511258.png
1305031119.547382 rgb/1305031119.547382.png 1305031119.547414 depth/1305031119.547414.png
1305031119.579559 rgb/1305031119.579559.png 1305031119.579569 depth/1305031119.579569.png
1305031119.615017 rgb/1305031119.615017.png 1305031119.615024 depth/1305031119.615024.png
1305031119.647903 rgb/1305031119.647903.png 1305031119.648889 depth/1305031119.648889.png
1305031119.679208 rgb/1305031119.679208.png 1305031119.675566 depth/1305031119.675566.png
1305031119.715232 rgb/1305031119.715232.png 1305031119.715249 depth/1305031119.715249.png
1305031119.747193 rgb/1305031119.747193.png 1305031119.744886 depth/1305031119.744886.png
1305031119.779169 rgb/1305031119.779169.png 1305031119.778628 depth/1305031119.778628.png
1305031119.814537 rgb/1305031119.814537.png 1305031119.814571 depth/1305031119.814571.png
1305031119.847429 rgb/1305031119.847429.png 1305031119.847445 depth/1305031119.847445.png
1305031119.879214 rgb/1305031119.879214.png 1305031119.879232 depth/1305031119.879232.png
1305031119.911401 rgb/1305031119.911401.png 1305031119.911424 depth/1305031119.911424.png
1305031119.947392 rgb/1305031119.947392.png 1305031119.947462 depth/1305031119.947462.png
1305031119.979537 rgb/1305031119.979537.png 1305031119.979546 depth/1305031119.979546.png
1305031120.015264 rgb/1305031120.015264.png 1305031120.015283 depth/1305031120.015283.png
1305031120.047290 rgb/1305031120.047290.png 1305031120.047310 depth/1305031120.047310.png
1305031120.079418 rgb/1305031120.079418.png 1305031120.075690 depth/1305031120.075690.png
1305031120.115232 rgb/1305031120.115232.png 1305031120.115249 depth/1305031120.115249.png
1305031120.148157 rgb/1305031120.148157.png 1305031120.148175 depth/1305031120.148175.png
1305031120.179246 rgb/1305031120.179246.png 1305031120.179261 depth/1305031120.179261.png
1305031120.215249 rgb/1305031120.215249.png 1305031120.215260 depth/1305031120.215260.png
1305031120.248003 rgb/1305031120.248003.png 1305031120.248018 depth/1305031120.248018.png
1305031120.279430 rgb/1305031120.279430.png 1305031120.279441 depth/1305031120.279441.png
1305031120.315196 rgb/1305031120.315196.png 1305031120.315213 depth/1305031120.315213.png
1305031120.347787 rgb/1305031120.347787.png 1305031120.347797 depth/1305031120.347797.png
1305031120.379437 rgb/1305031120.379437.png 1305031120.379446 depth/1305031120.379446.png
1305031120.415445 rgb/1305031120.415445.png 1305031120.415490 depth/1305031120.415490.png
1305031120.447417 rgb/1305031120.447417.png 1305031120.447433 depth/1305031120.447433.png
1305031120.479432 rgb/1305031120.479432.png 1305031120.475582 depth/1305031120.475582.png
1305031120.514819 rgb/1305031120.514819.png 1305031120.514877 depth/1305031120.514877.png
1305031120.547736 rgb/1305031120.547736.png 1305031120.547807 depth/1305031120.547807.png
1305031120.579551 rgb/1305031120.579551.png 1305031120.579559 depth/1305031120.579559.png
1305031120.615236 rgb/1305031120.615236.png 1305031120.615271 depth/1305031120.615271.png
1305031120.647354 rgb/1305031120.647354.png 1305031120.646607 depth/1305031120.646607.png
1305031120.679318 rgb/1305031120.679318.png 1305031120.678467 depth/1305031120.678467.png
1305031120.714522 rgb/1305031120.714522.png 1305031120.714553 depth/1305031120.714553.png
1305031120.747369 rgb/1305031120.747369.png 1305031120.747396 depth/1305031120.747396.png
1305031120.779894 rgb/1305031120.779894.png 1305031120.779908 depth/1305031120.779908.png
1305031120.814944 rgb/1305031120.814944.png 1305031120.814905 depth/1305031120.814905.png
1305031120.847921 rgb/1305031120.847921.png 1305031120.847942 depth/1305031120.847942.png
1305031120.883435 rgb/1305031120.883435.png 1305031120.883454 depth/1305031120.883454.png
1305031120.915444 rgb/1305031120.915444.png 1305031120.915454 depth/1305031120.915454.png
1305031120.947488 rgb/1305031120.947488.png 1305031120.947509 depth/1305031120.947509.png
1305031120.983366 rgb/1305031120.983366.png 1305031120.983390 depth/1305031120.983390.png
1305031121.015019 rgb/1305031121.015019.png 1305031121.015029 depth/1305031121.015029.png
1305031121.047498 rgb/1305031121.047498.png 1305031121.047755 depth/1305031121.047755.png
1305031121.083099 rgb/1305031121.083099.png 1305031121.083117 depth/1305031121.083117.png
1305031121.114696 rgb/1305031121.114696.png 1305031121.114878 depth/1305031121.114878.png
1305031121.147331 rgb/1305031121.147331.png 1305031121.147355 depth/1305031121.147355.png
1305031121.183271 rgb/1305031121.183271.png 1305031121.183281 depth/1305031121.183281.png
1305031121.211420 rgb/1305031121.211420.png 1305031121.211431 depth/1305031121.211431.png
1305031121.247194 rgb/1305031121.247194.png 1305031121.247201 depth/1305031121.247201.png
1305031121.282876 rgb/1305031121.282876.png 1305031121.282822 depth/1305031121.282822.png
1305031121.313568 rgb/1305031121.313568.png 1305031121.313588 depth/1305031121.313588.png
1305031121.347517 rgb/1305031121.347517.png 1305031121.347540 depth/1305031121.347540.png
1305031121.383226 rgb/1305031121.383226.png 1305031121.383248 depth/1305031121.383248.png
1305031121.414318 rgb/1305031121.414318.png 1305031121.414328 depth/1305031121.414328.png
1305031121.447319 rgb/1305031121.447319.png 1305031121.447024 depth/1305031121.447024.png
1305031121.482964 rgb/1305031121.482964.png 1305031121.483015 depth/1305031121.483015.png
1305031121.514107 rgb/1305031121.514107.png 1305031121.514164 depth/1305031121.514164.png
1305031121.547270 rgb/1305031121.547270.png 1305031121.546810 depth/1305031121.546810.png
1305031121.583204 rgb/1305031121.583204.png 1305031121.583213 depth/1305031121.583213.png
1305031121.614700 rgb/1305031121.614700.png 1305031121.614719 depth/1305031121.614719.png
1305031121.647183 rgb/1305031121.647183.png 1305031121.646966 depth/1305031121.646966.png
1305031121.683200 rgb/1305031121.683200.png 1305031121.683211 depth/1305031121.683211.png
1305031121.714520 rgb/1305031121.714520.png 1305031121.714528 depth/1305031121.714528.png
1305031121.747145 rgb/1305031121.747145.png 1305031121.746484 depth/1305031121.746484.png
1305031121.782835 rgb/1305031121.782835.png 1305031121.782871 depth/1305031121.782871.png
1305031121.811540 rgb/1305031121.811540.png 1305031121.811545 depth/1305031121.811545.png
1305031121.847335 rgb/1305031121.847335.png 1305031121.846870 depth/1305031121.846870.png
1305031121.882060 rgb/1305031121.882060.png 1305031121.882123 depth/1305031121.882123.png
1305031121.914931 rgb/1305031121.914931.png 1305031121.914943 depth/1305031121.914943.png
1305031121.947288 rgb/1305031121.947288.png 1305031121.947318 depth/1305031121.947318.png
1305031121.982926 rgb/1305031121.982926.png 1305031121.982935 depth/1305031121.982935.png
1305031122.014256 rgb/1305031122.014256.png 1305031122.014424 depth/1305031122.014424.png
1305031122.047306 rgb/1305031122.047306.png 1305031122.046908 depth/1305031122.046908.png
1305031122.082959 rgb/1305031122.082959.png 1305031122.082969 depth/1305031122.082969.png
1305031122.114672 rgb/1305031122.114672.png 1305031122.114688 depth/1305031122.114688.png
1305031122.150725 rgb/1305031122.150725.png 1305031122.150748 depth/1305031122.150748.png
1305031122.183042 rgb/1305031122.183042.png 1305031122.183052 depth/1305031122.183052.png
1305031122.214959 rgb/1305031122.214959.png 1305031122.214969 depth/1305031122.214969.png
1305031122.251319 rgb/1305031122.251319.png 1305031122.251355 depth/1305031122.251355.png
1305031122.283560 rgb/1305031122.283560.png 1305031122.283866 depth/1305031122.283866.png
1305031122.314289 rgb/1305031122.314289.png 1305031122.314309 depth/1305031122.314309.png
1305031122.351327 rgb/1305031122.351327.png 1305031122.351351 depth/1305031122.351351.png
1305031122.382630 rgb/1305031122.382630.png 1305031122.382678 depth/1305031122.382678.png
1305031122.414997 rgb/1305031122.414997.png 1305031122.415008 depth/1305031122.415008.png
1305031122.451257 rgb/1305031122.451257.png 1305031122.451272 depth/1305031122.451272.png
1305031122.483360 rgb/1305031122.483360.png 1305031122.483388 depth/1305031122.483388.png
1305031122.515097 rgb/1305031122.515097.png 1305031122.515135 depth/1305031122.515135.png
1305031122.551490 rgb/1305031122.551490.png 1305031122.551510 depth/1305031122.551510.png
1305031122.583208 rgb/1305031122.583208.png 1305031122.583217 depth/1305031122.583217.png
1305031122.614980 rgb/1305031122.614980.png 1305031122.615017 depth/1305031122.615017.png
1305031122.648788 rgb/1305031122.648788.png 1305031122.648810 depth/1305031122.648810.png
1305031122.683402 rgb/1305031122.683402.png 1305031122.683420 depth/1305031122.683420.png
1305031122.715208 rgb/1305031122.715208.png 1305031122.715219 depth/1305031122.715219.png
1305031122.751298 rgb/1305031122.751298.png 1305031122.751309 depth/1305031122.751309.png
1305031122.783423 rgb/1305031122.783423.png 1305031122.783438 depth/1305031122.783438.png
1305031122.812555 rgb/1305031122.812555.png 1305031122.812565 depth/1305031122.812565.png
1305031122.851418 rgb/1305031122.851418.png 1305031122.851486 depth/1305031122.851486.png
1305031122.883754 rgb/1305031122.883754.png 1305031122.883775 depth/1305031122.883775.png
1305031122.914571 rgb/1305031122.914571.png 1305031122.914585 depth/1305031122.914585.png
1305031122.951341 rgb/1305031122.951341.png 1305031122.951413 depth/1305031122.951413.png
1305031122.982815 rgb/1305031122.982815.png 1305031122.983000 depth/1305031122.983000.png
1305031123.015450 rgb/1305031123.015450.png 1305031123.015462 depth/1305031123.015462.png
1305031123.051827 rgb/1305031123.051827.png 1305031123.051838 depth/1305031123.051838.png
1305031123.082975 rgb/1305031123.082975.png 1305031123.082992 depth/1305031123.082992.png
1305031123.113873 rgb/1305031123.113873.png 1305031123.113939 depth/1305031123.113939.png
1305031123.150822 rgb/1305031123.150822.png 1305031123.150840 depth/1305031123.150840.png
1305031123.182155 rgb/1305031123.182155.png 1305031123.182176 depth/1305031123.182176.png
1305031123.214704 rgb/1305031123.214704.png 1305031123.214724 depth/1305031123.214724.png
1305031123.250618 rgb/1305031123.250618.png 1305031123.250641 depth/1305031123.250641.png
1305031123.282347 rgb/1305031123.282347.png 1305031123.282363 depth/1305031123.282363.png
1305031123.311327 rgb/1305031123.311327.png 1305031123.320992 depth/1305031123.320992.png
1305031123.350481 rgb/1305031123.350481.png 1305031123.350493 depth/1305031123.350493.png
1305031123.382255 rgb/1305031123.382255.png 1305031123.382263 depth/1305031123.382263.png
1305031123.411363 rgb/1305031123.411363.png 1305031123.421343 depth/1305031123.421343.png
1305031123.451255 rgb/1305031123.451255.png 1305031123.451266 depth/1305031123.451266.png
1305031123.483594 rgb/1305031123.483594.png 1305031123.483605 depth/1305031123.483605.png
1305031123.511360 rgb/1305031123.511360.png 1305031123.519725 depth/1305031123.519725.png
1305031123.551513 rgb/1305031123.551513.png 1305031123.551573 depth/1305031123.551573.png
1305031123.579583 rgb/1305031123.579583.png 1305031123.579616 depth/1305031123.579616.png
1305031123.611335 rgb/1305031123.611335.png 1305031123.620387 depth/1305031123.620387.png
1305031123.652411 rgb/1305031123.652411.png 1305031123.652430 depth/1305031123.652430.png
1305031123.683753 rgb/1305031123.683753.png 1305031123.683785 depth/1305031123.683785.png
1305031123.711323 rgb/1305031123.711323.png 1305031123.719975 depth/1305031123.719975.png
1305031123.751723 rgb/1305031123.751723.png 1305031123.751980 depth/1305031123.751980.png
1305031123.783858 rgb/1305031123.783858.png 1305031123.784138 depth/1305031123.784138.png
1305031123.811608 rgb/1305031123.811608.png 1305031123.819696 depth/1305031123.819696.png
1305031123.851444 rgb/1305031123.851444.png 1305031123.851551 depth/1305031123.851551.png
1305031123.883786 rgb/1305031123.883786.png 1305031123.883819 depth/1305031123.883819.png
1305031123.911243 rgb/1305031123.911243.png 1305031123.915794 depth/1305031123.915794.png
1305031123.951442 rgb/1305031123.951442.png 1305031123.951530 depth/1305031123.951530.png
1305031123.983415 rgb/1305031123.983415.png 1305031123.983421 depth/1305031123.983421.png
1305031124.011302 rgb/1305031124.011302.png 1305031124.019737 depth/1305031124.019737.png
1305031124.051505 rgb/1305031124.051505.png 1305031124.051531 depth/1305031124.051531.png
1305031124.083837 rgb/1305031124.083837.png 1305031124.083902 depth/1305031124.083902.png
1305031124.111331 rgb/1305031124.111331.png 1305031124.119669 depth/1305031124.119669.png
1305031124.147446 rgb/1305031124.147446.png 1305031124.147458 depth/1305031124.147458.png
1305031124.182694 rgb/1305031124.182694.png 1305031124.182707 depth/1305031124.182707.png
1305031124.211396 rgb/1305031124.211396.png 1305031124.217179 depth/1305031124.217179.png
1305031124.249327 rgb/1305031124.249327.png 1305031124.249340 depth/1305031124.249340.png
1305031124.282545 rgb/1305031124.282545.png 1305031124.282555 depth/1305031124.282555.png
1305031124.311361 rgb/1305031124.311361.png 1305031124.316782 depth/1305031124.316782.png
1305031124.350354 rgb/1305031124.350354.png 1305031124.350371 depth/1305031124.350371.png
1305031124.382420 rgb/1305031124.382420.png 1305031124.382432 depth/1305031124.382432.png
1305031124.411439 rgb/1305031124.411439.png 1305031124.418555 depth/1305031124.418555.png
1305031124.450245 rgb/1305031124.450245.png 1305031124.450256 depth/1305031124.450256.png
1305031124.480099 rgb/1305031124.480099.png 1305031124.480126 depth/1305031124.480126.png
1305031124.511324 rgb/1305031124.511324.png 1305031124.516737 depth/1305031124.516737.png
1305031124.550437 rgb/1305031124.550437.png 1305031124.550503 depth/1305031124.550503.png
1305031124.579404 rgb/1305031124.579404.png 1305031124.584606 depth/1305031124.584606.png
1305031124.611358 rgb/1305031124.611358.png 1305031124.617653 depth/1305031124.617653.png
1305031124.651271 rgb/1305031124.651271.png 1305031124.651313 depth/1305031124.651313.png
1305031124.679362 rgb/1305031124.679362.png 1305031124.685473 depth/1305031124.685473.png
1305031124.711251 rgb/1305031124.711251.png 1305031124.715791 depth/1305031124.715791.png
1305031124.749890 rgb/1305031124.749890.png 1305031124.749941 depth/1305031124.749941.png
1305031124.779365 rgb/1305031124.779365.png 1305031124.785178 depth/1305031124.785178.png
1305031124.811360 rgb/1305031124.811360.png 1305031124.816641 depth/1305031124.816641.png
1305031124.850535 rgb/1305031124.850535.png 1305031124.850559 depth/1305031124.850559.png
1305031124.879355 rgb/1305031124.879355.png 1305031124.883594 depth/1305031124.883594.png
1305031124.911448 rgb/1305031124.911448.png 1305031124.918770 depth/1305031124.918770.png
1305031124.950730 rgb/1305031124.950730.png 1305031124.950748 depth/1305031124.950748.png
1305031124.979438 rgb/1305031124.979438.png 1305031124.986460 depth/1305031124.986460.png
1305031125.011454 rgb/1305031125.011454.png 1305031125.019467 depth/1305031125.019467.png
1305031125.050763 rgb/1305031125.050763.png 1305031125.050798 depth/1305031125.050798.png
1305031125.079364 rgb/1305031125.079364.png 1305031125.083480 depth/1305031125.083480.png
1305031125.111364 rgb/1305031125.111364.png 1305031125.119029 depth/1305031125.119029.png
1305031125.151013 rgb/1305031125.151013.png 1305031125.151037 depth/1305031125.151037.png
1305031125.179353 rgb/1305031125.179353.png 1305031125.187064 depth/1305031125.187064.png
1305031125.211320 rgb/1305031125.211320.png 1305031125.219018 depth/1305031125.219018.png
1305031125.250632 rgb/1305031125.250632.png 1305031125.250642 depth/1305031125.250642.png
1305031125.279467 rgb/1305031125.279467.png 1305031125.286396 depth/1305031125.286396.png
1305031125.311493 rgb/1305031125.311493.png 1305031125.319140 depth/1305031125.319140.png
1305031125.348880 rgb/1305031125.348880.png 1305031125.348899 depth/1305031125.348899.png
1305031125.379401 rgb/1305031125.379401.png 1305031125.386792 depth/1305031125.386792.png
1305031125.411335 rgb/1305031125.411335.png 1305031125.419574 depth/1305031125.419574.png
1305031125.451195 rgb/1305031125.451195.png 1305031125.451232 depth/1305031125.451232.png
1305031125.479424 rgb/1305031125.479424.png 1305031125.486999 depth/1305031125.486999.png
1305031125.511316 rgb/1305031125.511316.png 1305031125.519354 depth/1305031125.519354.png
1305031125.551020 rgb/1305031125.551020.png 1305031125.551050 depth/1305031125.551050.png
1305031125.579308 rgb/1305031125.579308.png 1305031125.585303 depth/1305031125.585303.png
1305031125.611533 rgb/1305031125.611533.png 1305031125.617870 depth/1305031125.617870.png
1305031125.650575 rgb/1305031125.650575.png 1305031125.650354 depth/1305031125.650354.png
1305031125.679328 rgb/1305031125.679328.png 1305031125.684602 depth/1305031125.684602.png
1305031125.711443 rgb/1305031125.711443.png 1305031125.715669 depth/1305031125.715669.png
1305031125.751260 rgb/1305031125.751260.png 1305031125.751292 depth/1305031125.751292.png
1305031125.779348 rgb/1305031125.779348.png 1305031125.786805 depth/1305031125.786805.png
1305031125.811573 rgb/1305031125.811573.png 1305031125.819450 depth/1305031125.819450.png
1305031125.847412 rgb/1305031125.847412.png 1305031125.854774 depth/1305031125.854774.png
1305031125.879318 rgb/1305031125.879318.png 1305031125.886645 depth/1305031125.886645.png
1305031125.911305 rgb/1305031125.911305.png 1305031125.919334 depth/1305031125.919334.png
1305031125.947343 rgb/1305031125.947343.png 1305031125.955252 depth/1305031125.955252.png
1305031125.979324 rgb/1305031125.979324.png 1305031125.987094 depth/1305031125.987094.png
1305031126.011333 rgb/1305031126.011333.png 1305031126.019572 depth/1305031126.019572.png
1305031126.047324 rgb/1305031126.047324.png 1305031126.055038 depth/1305031126.055038.png
1305031126.079356 rgb/1305031126.079356.png 1305031126.087076 depth/1305031126.087076.png
1305031126.111370 rgb/1305031126.111370.png 1305031126.119452 depth/1305031126.119452.png
1305031126.147432 rgb/1305031126.147432.png 1305031126.155000 depth/1305031126.155000.png
1305031126.179384 rgb/1305031126.179384.png 1305031126.187174 depth/1305031126.187174.png
1305031126.211319 rgb/1305031126.211319.png 1305031126.219473 depth/1305031126.219473.png
1305031126.247298 rgb/1305031126.247298.png 1305031126.255236 depth/1305031126.255236.png
1305031126.279363 rgb/1305031126.279363.png 1305031126.287105 depth/1305031126.287105.png
1305031126.311332 rgb/1305031126.311332.png 1305031126.319787 depth/1305031126.319787.png
1305031126.347363 rgb/1305031126.347363.png 1305031126.355415 depth/1305031126.355415.png
1305031126.379423 rgb/1305031126.379423.png 1305031126.387483 depth/1305031126.387483.png
1305031126.411465 rgb/1305031126.411465.png 1305031126.419793 depth/1305031126.419793.png
1305031126.447361 rgb/1305031126.447361.png 1305031126.455380 depth/1305031126.455380.png
1305031126.479533 rgb/1305031126.479533.png 1305031126.490386 depth/1305031126.490386.png
1305031126.511410 rgb/1305031126.511410.png 1305031126.522321 depth/1305031126.522321.png
1305031126.547374 rgb/1305031126.547374.png 1305031126.558209 depth/1305031126.558209.png
1305031126.579454 rgb/1305031126.579454.png 1305031126.590176 depth/1305031126.590176.png
1305031126.611528 rgb/1305031126.611528.png 1305031126.618687 depth/1305031126.618687.png
1305031126.647376 rgb/1305031126.647376.png 1305031126.654474 depth/1305031126.654474.png
1305031126.679479 rgb/1305031126.679479.png 1305031126.690022 depth/1305031126.690022.png
1305031126.711583 rgb/1305031126.711583.png 1305031126.715770 depth/1305031126.715770.png
1305031126.747316 rgb/1305031126.747316.png 1305031126.755374 depth/1305031126.755374.png
1305031126.779379 rgb/1305031126.779379.png 1305031126.787565 depth/1305031126.787565.png
1305031126.811602 rgb/1305031126.811602.png 1305031126.819929 depth/1305031126.819929.png
1305031126.847343 rgb/1305031126.847343.png 1305031126.858378 depth/1305031126.858378.png
1305031126.879357 rgb/1305031126.879357.png 1305031126.888154 depth/1305031126.888154.png
1305031126.911364 rgb/1305031126.911364.png 1305031126.919409 depth/1305031126.919409.png
1305031126.947437 rgb/1305031126.947437.png 1305031126.955501 depth/1305031126.955501.png
1305031126.979337 rgb/1305031126.979337.png 1305031126.987316 depth/1305031126.987316.png
1305031127.011371 rgb/1305031127.011371.png 1305031127.019524 depth/1305031127.019524.png
1305031127.047297 rgb/1305031127.047297.png 1305031127.053318 depth/1305031127.053318.png
1305031127.079299 rgb/1305031127.079299.png 1305031127.088649 depth/1305031127.088649.png
1305031127.111435 rgb/1305031127.111435.png 1305031127.120963 depth/1305031127.120963.png
1305031127.147307 rgb/1305031127.147307.png 1305031127.157692 depth/1305031127.157692.png
1305031127.179349 rgb/1305031127.179349.png 1305031127.187500 depth/1305031127.187500.png
1305031127.211700 rgb/1305031127.211700.png 1305031127.221831 depth/1305031127.221831.png
1305031127.247374 rgb/1305031127.247374.png 1305031127.259761 depth/1305031127.259761.png
1305031127.279465 rgb/1305031127.279465.png 1305031127.287038 depth/1305031127.287038.png
1305031127.311362 rgb/1305031127.311362.png 1305031127.320468 depth/1305031127.320468.png
1305031127.347356 rgb/1305031127.347356.png 1305031127.353407 depth/1305031127.353407.png
1305031127.379262 rgb/1305031127.379262.png 1305031127.383713 depth/1305031127.383713.png
1305031127.411371 rgb/1305031127.411371.png 1305031127.419650 depth/1305031127.419650.png
1305031127.447333 rgb/1305031127.447333.png 1305031127.454246 depth/1305031127.454246.png
1305031127.479362 rgb/1305031127.479362.png 1305031127.487200 depth/1305031127.487200.png
1305031127.511356 rgb/1305031127.511356.png 1305031127.521900 depth/1305031127.521900.png
1305031127.547348 rgb/1305031127.547348.png 1305031127.553725 depth/1305031127.553725.png
1305031127.579345 rgb/1305031127.579345.png 1305031127.586632 depth/1305031127.586632.png
1305031127.611271 rgb/1305031127.611271.png 1305031127.620657 depth/1305031127.620657.png
1305031127.647358 rgb/1305031127.647358.png 1305031127.654656 depth/1305031127.654656.png
1305031127.679298 rgb/1305031127.679298.png 1305031127.687110 depth/1305031127.687110.png
1305031127.711375 rgb/1305031127.711375.png 1305031127.723210 depth/1305031127.723210.png
1305031127.747304 rgb/1305031127.747304.png 1305031127.754694 depth/1305031127.754694.png
1305031127.779346 rgb/1305031127.779346.png 1305031127.787641 depth/1305031127.787641.png
1305031127.811829 rgb/1305031127.811829.png 1305031127.820128 depth/1305031127.820128.png
1305031127.847366 rgb/1305031127.847366.png 1305031127.855132 depth/1305031127.855132.png
1305031127.879380 rgb/1305031127.879380.png 1305031127.887122 depth/1305031127.887122.png
1305031127.911476 rgb/1305031127.911476.png 1305031127.922560 depth/1305031127.922560.png
1305031127.947366 rgb/1305031127.947366.png 1305031127.955088 depth/1305031127.955088.png
1305031127.979371 rgb/1305031127.979371.png 1305031127.987093 depth/1305031127.987093.png
1305031128.011427 rgb/1305031128.011427.png 1305031128.021776 depth/1305031128.021776.png
1305031128.047369 rgb/1305031128.047369.png 1305031128.055718 depth/1305031128.055718.png
1305031128.079334 rgb/1305031128.079334.png 1305031128.087206 depth/1305031128.087206.png
1305031128.111391 rgb/1305031128.111391.png 1305031128.124746 depth/1305031128.124746.png
1305031128.147418 rgb/1305031128.147418.png 1305031128.157782 depth/1305031128.157782.png
1305031128.179350 rgb/1305031128.179350.png 1305031128.187221 depth/1305031128.187221.png
1305031128.211447 rgb/1305031128.211447.png 1305031128.225442 depth/1305031128.225442.png
1305031128.247480 rgb/1305031128.247480.png 1305031128.256007 depth/1305031128.256007.png
1305031128.279336 rgb/1305031128.279336.png 1305031128.291275 depth/1305031128.291275.png
1305031128.311483 rgb/1305031128.311483.png 1305031128.324170 depth/1305031128.324170.png
1305031128.347423 rgb/1305031128.347423.png 1305031128.355206 depth/1305031128.355206.png
1305031128.379404 rgb/1305031128.379404.png 1305031128.391397 depth/1305031128.391397.png
1305031128.411337 rgb/1305031128.411337.png 1305031128.423609 depth/1305031128.423609.png
1305031128.447296 rgb/1305031128.447296.png 1305031128.455499 depth/1305031128.455499.png
1305031128.479296 rgb/1305031128.479296.png 1305031128.489523 depth/1305031128.489523.png
1305031128.511433 rgb/1305031128.511433.png 1305031128.523604 depth/1305031128.523604.png
1305031128.547399 rgb/1305031128.547399.png 1305031128.555639 depth/1305031128.555639.png
1305031128.579455 rgb/1305031128.579455.png 1305031128.591460 depth/1305031128.591460.png
1305031128.611395 rgb/1305031128.611395.png 1305031128.623368 depth/1305031128.623368.png
1305031128.647352 rgb/1305031128.647352.png 1305031128.655554 depth/1305031128.655554.png
1305031128.679282 rgb/1305031128.679282.png 1305031128.690449 depth/1305031128.690449.png
1305031128.711457 rgb/1305031128.711457.png 1305031128.722976 depth/1305031128.722976.png
1305031128.747363 rgb/1305031128.747363.png 1305031128.754646 depth/1305031128.754646.png
================================================
FILE: Examples/RGB-D/associations/fr2_desk.txt
================================================
1311868164.363181 rgb/1311868164.363181.png 1311868164.373557 depth/1311868164.373557.png
1311868164.399026 rgb/1311868164.399026.png 1311868164.407784 depth/1311868164.407784.png
1311868164.430940 rgb/1311868164.430940.png 1311868164.437021 depth/1311868164.437021.png
1311868164.463055 rgb/1311868164.463055.png 1311868164.477039 depth/1311868164.477039.png
1311868164.499130 rgb/1311868164.499130.png 1311868164.507698 depth/1311868164.507698.png
1311868164.531025 rgb/1311868164.531025.png 1311868164.539395 depth/1311868164.539395.png
1311868164.563004 rgb/1311868164.563004.png 1311868164.573050 depth/1311868164.573050.png
1311868164.599061 rgb/1311868164.599061.png 1311868164.607892 depth/1311868164.607892.png
1311868164.631140 rgb/1311868164.631140.png 1311868164.637394 depth/1311868164.637394.png
1311868164.663105 rgb/1311868164.663105.png 1311868164.677534 depth/1311868164.677534.png
1311868164.698987 rgb/1311868164.698987.png 1311868164.709615 depth/1311868164.709615.png
1311868164.731046 rgb/1311868164.731046.png 1311868164.737662 depth/1311868164.737662.png
1311868164.763098 rgb/1311868164.763098.png 1311868164.779225 depth/1311868164.779225.png
1311868164.799138 rgb/1311868164.799138.png 1311868164.809404 depth/1311868164.809404.png
1311868164.831006 rgb/1311868164.831006.png 1311868164.842880 depth/1311868164.842880.png
1311868164.863058 rgb/1311868164.863058.png 1311868164.874612 depth/1311868164.874612.png
1311868164.899132 rgb/1311868164.899132.png 1311868164.905168 depth/1311868164.905168.png
1311868164.930933 rgb/1311868164.930933.png 1311868164.941784 depth/1311868164.941784.png
1311868164.963119 rgb/1311868164.963119.png 1311868164.975315 depth/1311868164.975315.png
1311868164.999037 rgb/1311868164.999037.png 1311868165.006447 depth/1311868165.006447.png
1311868165.031122 rgb/1311868165.031122.png 1311868165.043301 depth/1311868165.043301.png
1311868165.063108 rgb/1311868165.063108.png 1311868165.077013 depth/1311868165.077013.png
1311868165.099162 rgb/1311868165.099162.png 1311868165.107584 depth/1311868165.107584.png
1311868165.131014 rgb/1311868165.131014.png 1311868165.140672 depth/1311868165.140672.png
1311868165.163146 rgb/1311868165.163146.png 1311868165.173990 depth/1311868165.173990.png
1311868165.199145 rgb/1311868165.199145.png 1311868165.207186 depth/1311868165.207186.png
1311868165.231193 rgb/1311868165.231193.png 1311868165.241540 depth/1311868165.241540.png
1311868165.263005 rgb/1311868165.263005.png 1311868165.276310 depth/1311868165.276310.png
1311868165.299103 rgb/1311868165.299103.png 1311868165.309970 depth/1311868165.309970.png
1311868165.331226 rgb/1311868165.331226.png 1311868165.341279 depth/1311868165.341279.png
1311868165.363060 rgb/1311868165.363060.png 1311868165.373166 depth/1311868165.373166.png
1311868165.399160 rgb/1311868165.399160.png 1311868165.409979 depth/1311868165.409979.png
1311868165.430962 rgb/1311868165.430962.png 1311868165.441768 depth/1311868165.441768.png
1311868165.463114 rgb/1311868165.463114.png 1311868165.476336 depth/1311868165.476336.png
1311868165.499179 rgb/1311868165.499179.png 1311868165.507271 depth/1311868165.507271.png
1311868165.531124 rgb/1311868165.531124.png 1311868165.546047 depth/1311868165.546047.png
1311868165.563054 rgb/1311868165.563054.png 1311868165.574653 depth/1311868165.574653.png
1311868165.599188 rgb/1311868165.599188.png 1311868165.607633 depth/1311868165.607633.png
1311868165.631159 rgb/1311868165.631159.png 1311868165.645161 depth/1311868165.645161.png
1311868165.663251 rgb/1311868165.663251.png 1311868165.678824 depth/1311868165.678824.png
1311868165.699187 rgb/1311868165.699187.png 1311868165.704839 depth/1311868165.704839.png
1311868165.731234 rgb/1311868165.731234.png 1311868165.744880 depth/1311868165.744880.png
1311868165.763100 rgb/1311868165.763100.png 1311868165.773032 depth/1311868165.773032.png
1311868165.799107 rgb/1311868165.799107.png 1311868165.812385 depth/1311868165.812385.png
1311868165.831186 rgb/1311868165.831186.png 1311868165.841804 depth/1311868165.841804.png
1311868165.863220 rgb/1311868165.863220.png 1311868165.877856 depth/1311868165.877856.png
1311868165.899162 rgb/1311868165.899162.png 1311868165.906859 depth/1311868165.906859.png
1311868165.931154 rgb/1311868165.931154.png 1311868165.940588 depth/1311868165.940588.png
1311868165.963154 rgb/1311868165.963154.png 1311868165.976324 depth/1311868165.976324.png
1311868165.999133 rgb/1311868165.999133.png 1311868166.007658 depth/1311868166.007658.png
1311868166.031204 rgb/1311868166.031204.png 1311868166.045983 depth/1311868166.045983.png
1311868166.063111 rgb/1311868166.063111.png 1311868166.076013 depth/1311868166.076013.png
1311868166.099206 rgb/1311868166.099206.png 1311868166.114132 depth/1311868166.114132.png
1311868166.131254 rgb/1311868166.131254.png 1311868166.142743 depth/1311868166.142743.png
1311868166.163189 rgb/1311868166.163189.png 1311868166.179610 depth/1311868166.179610.png
1311868166.199211 rgb/1311868166.199211.png 1311868166.210624 depth/1311868166.210624.png
1311868166.231050 rgb/1311868166.231050.png 1311868166.247913 depth/1311868166.247913.png
1311868166.263177 rgb/1311868166.263177.png 1311868166.277838 depth/1311868166.277838.png
1311868166.299209 rgb/1311868166.299209.png 1311868166.315342 depth/1311868166.315342.png
1311868166.331189 rgb/1311868166.331189.png 1311868166.343165 depth/1311868166.343165.png
1311868166.363122 rgb/1311868166.363122.png 1311868166.377872 depth/1311868166.377872.png
1311868166.399232 rgb/1311868166.399232.png 1311868166.412308 depth/1311868166.412308.png
1311868166.431171 rgb/1311868166.431171.png 1311868166.446657 depth/1311868166.446657.png
1311868166.463018 rgb/1311868166.463018.png 1311868166.473009 depth/1311868166.473009.png
1311868166.499195 rgb/1311868166.499195.png 1311868166.513359 depth/1311868166.513359.png
1311868166.531252 rgb/1311868166.531252.png 1311868166.548698 depth/1311868166.548698.png
1311868166.563132 rgb/1311868166.563132.png 1311868166.575428 depth/1311868166.575428.png
1311868166.599207 rgb/1311868166.599207.png 1311868166.615820 depth/1311868166.615820.png
1311868166.631287 rgb/1311868166.631287.png 1311868166.646341 depth/1311868166.646341.png
1311868166.663284 rgb/1311868166.663284.png 1311868166.674028 depth/1311868166.674028.png
1311868166.699270 rgb/1311868166.699270.png 1311868166.715787 depth/1311868166.715787.png
1311868166.731105 rgb/1311868166.731105.png 1311868166.742696 depth/1311868166.742696.png
1311868166.763333 rgb/1311868166.763333.png 1311868166.778154 depth/1311868166.778154.png
1311868166.799225 rgb/1311868166.799225.png 1311868166.815856 depth/1311868166.815856.png
1311868166.831229 rgb/1311868166.831229.png 1311868166.842696 depth/1311868166.842696.png
1311868166.863222 rgb/1311868166.863222.png 1311868166.878523 depth/1311868166.878523.png
1311868166.899308 rgb/1311868166.899308.png 1311868166.912315 depth/1311868166.912315.png
1311868166.931160 rgb/1311868166.931160.png 1311868166.944305 depth/1311868166.944305.png
1311868166.963312 rgb/1311868166.963312.png 1311868166.974973 depth/1311868166.974973.png
1311868166.999289 rgb/1311868166.999289.png 1311868167.013110 depth/1311868167.013110.png
1311868167.031127 rgb/1311868167.031127.png 1311868167.042581 depth/1311868167.042581.png
1311868167.063209 rgb/1311868167.063209.png 1311868167.078817 depth/1311868167.078817.png
1311868167.099303 rgb/1311868167.099303.png 1311868167.113263 depth/1311868167.113263.png
1311868167.163230 rgb/1311868167.163230.png 1311868167.147601 depth/1311868167.147601.png
1311868167.199258 rgb/1311868167.199258.png 1311868167.213735 depth/1311868167.213735.png
1311868167.231267 rgb/1311868167.231267.png 1311868167.244725 depth/1311868167.244725.png
1311868167.263251 rgb/1311868167.263251.png 1311868167.274291 depth/1311868167.274291.png
1311868167.299141 rgb/1311868167.299141.png 1311868167.313892 depth/1311868167.313892.png
1311868167.331145 rgb/1311868167.331145.png 1311868167.343051 depth/1311868167.343051.png
1311868167.363275 rgb/1311868167.363275.png 1311868167.382523 depth/1311868167.382523.png
1311868167.399226 rgb/1311868167.399226.png 1311868167.412495 depth/1311868167.412495.png
1311868167.431237 rgb/1311868167.431237.png 1311868167.443001 depth/1311868167.443001.png
1311868167.463303 rgb/1311868167.463303.png 1311868167.480198 depth/1311868167.480198.png
1311868167.499121 rgb/1311868167.499121.png 1311868167.512612 depth/1311868167.512612.png
1311868167.531321 rgb/1311868167.531321.png 1311868167.545938 depth/1311868167.545938.png
1311868167.563160 rgb/1311868167.563160.png 1311868167.579040 depth/1311868167.579040.png
1311868167.599230 rgb/1311868167.599230.png 1311868167.613541 depth/1311868167.613541.png
1311868167.631495 rgb/1311868167.631495.png 1311868167.646201 depth/1311868167.646201.png
1311868167.663360 rgb/1311868167.663360.png 1311868167.682062 depth/1311868167.682062.png
1311868167.699226 rgb/1311868167.699226.png 1311868167.711828 depth/1311868167.711828.png
1311868167.731241 rgb/1311868167.731241.png 1311868167.747549 depth/1311868167.747549.png
1311868167.763281 rgb/1311868167.763281.png 1311868167.778192 depth/1311868167.778192.png
1311868167.799224 rgb/1311868167.799224.png 1311868167.811077 depth/1311868167.811077.png
1311868167.863098 rgb/1311868167.863098.png 1311868167.847649 depth/1311868167.847649.png
1311868167.899376 rgb/1311868167.899376.png 1311868167.914863 depth/1311868167.914863.png
1311868167.931184 rgb/1311868167.931184.png 1311868167.944131 depth/1311868167.944131.png
1311868167.999325 rgb/1311868167.999325.png 1311868168.014342 depth/1311868168.014342.png
1311868168.031266 rgb/1311868168.031266.png 1311868168.047735 depth/1311868168.047735.png
1311868168.063183 rgb/1311868168.063183.png 1311868168.076594 depth/1311868168.076594.png
1311868168.099296 rgb/1311868168.099296.png 1311868168.115940 depth/1311868168.115940.png
1311868168.131162 rgb/1311868168.131162.png 1311868168.141624 depth/1311868168.141624.png
1311868168.163282 rgb/1311868168.163282.png 1311868168.180912 depth/1311868168.180912.png
1311868168.199247 rgb/1311868168.199247.png 1311868168.210991 depth/1311868168.210991.png
1311868168.263256 rgb/1311868168.263256.png 1311868168.247820 depth/1311868168.247820.png
1311868168.299606 rgb/1311868168.299606.png 1311868168.318349 depth/1311868168.318349.png
1311868168.331222 rgb/1311868168.331222.png 1311868168.342592 depth/1311868168.342592.png
1311868168.363180 rgb/1311868168.363180.png 1311868168.379082 depth/1311868168.379082.png
1311868168.399360 rgb/1311868168.399360.png 1311868168.414678 depth/1311868168.414678.png
1311868168.431214 rgb/1311868168.431214.png 1311868168.442322 depth/1311868168.442322.png
1311868168.463333 rgb/1311868168.463333.png 1311868168.480727 depth/1311868168.480727.png
1311868168.499268 rgb/1311868168.499268.png 1311868168.511764 depth/1311868168.511764.png
1311868168.563319 rgb/1311868168.563319.png 1311868168.549203 depth/1311868168.549203.png
1311868168.599366 rgb/1311868168.599366.png 1311868168.613771 depth/1311868168.613771.png
1311868168.663320 rgb/1311868168.663320.png 1311868168.647259 depth/1311868168.647259.png
1311868168.699557 rgb/1311868168.699557.png 1311868168.712769 depth/1311868168.712769.png
1311868168.763305 rgb/1311868168.763305.png 1311868168.747597 depth/1311868168.747597.png
1311868168.799362 rgb/1311868168.799362.png 1311868168.813606 depth/1311868168.813606.png
1311868168.831176 rgb/1311868168.831176.png 1311868168.846276 depth/1311868168.846276.png
1311868168.899300 rgb/1311868168.899300.png 1311868168.881883 depth/1311868168.881883.png
1311868168.931215 rgb/1311868168.931215.png 1311868168.916265 depth/1311868168.916265.png
1311868168.963348 rgb/1311868168.963348.png 1311868168.947866 depth/1311868168.947866.png
1311868168.999373 rgb/1311868168.999373.png 1311868169.015053 depth/1311868169.015053.png
1311868169.031214 rgb/1311868169.031214.png 1311868169.046000 depth/1311868169.046000.png
1311868169.063354 rgb/1311868169.063354.png 1311868169.080829 depth/1311868169.080829.png
1311868169.099339 rgb/1311868169.099339.png 1311868169.114700 depth/1311868169.114700.png
1311868169.131247 rgb/1311868169.131247.png 1311868169.146187 depth/1311868169.146187.png
1311868169.199452 rgb/1311868169.199452.png 1311868169.212807 depth/1311868169.212807.png
1311868169.231354 rgb/1311868169.231354.png 1311868169.247722 depth/1311868169.247722.png
1311868169.263274 rgb/1311868169.263274.png 1311868169.278346 depth/1311868169.278346.png
1311868169.299529 rgb/1311868169.299529.png 1311868169.314714 depth/1311868169.314714.png
1311868169.331297 rgb/1311868169.331297.png 1311868169.345199 depth/1311868169.345199.png
1311868169.363470 rgb/1311868169.363470.png 1311868169.381298 depth/1311868169.381298.png
1311868169.399437 rgb/1311868169.399437.png 1311868169.415209 depth/1311868169.415209.png
1311868169.431440 rgb/1311868169.431440.png 1311868169.448276 depth/1311868169.448276.png
1311868169.463229 rgb/1311868169.463229.png 1311868169.476415 depth/1311868169.476415.png
1311868169.499263 rgb/1311868169.499263.png 1311868169.510002 depth/1311868169.510002.png
1311868169.531434 rgb/1311868169.531434.png 1311868169.546064 depth/1311868169.546064.png
1311868169.563501 rgb/1311868169.563501.png 1311868169.578266 depth/1311868169.578266.png
1311868169.599378 rgb/1311868169.599378.png 1311868169.611451 depth/1311868169.611451.png
1311868169.631327 rgb/1311868169.631327.png 1311868169.645864 depth/1311868169.645864.png
1311868169.663240 rgb/1311868169.663240.png 1311868169.676560 depth/1311868169.676560.png
1311868169.699466 rgb/1311868169.699466.png 1311868169.710206 depth/1311868169.710206.png
1311868169.731279 rgb/1311868169.731279.png 1311868169.744399 depth/1311868169.744399.png
1311868169.763417 rgb/1311868169.763417.png 1311868169.777125 depth/1311868169.777125.png
1311868169.799368 rgb/1311868169.799368.png 1311868169.813053 depth/1311868169.813053.png
1311868169.831415 rgb/1311868169.831415.png 1311868169.844213 depth/1311868169.844213.png
1311868169.863396 rgb/1311868169.863396.png 1311868169.876056 depth/1311868169.876056.png
1311868169.899390 rgb/1311868169.899390.png 1311868169.914497 depth/1311868169.914497.png
1311868169.931272 rgb/1311868169.931272.png 1311868169.944115 depth/1311868169.944115.png
1311868169.963415 rgb/1311868169.963415.png 1311868169.976205 depth/1311868169.976205.png
1311868169.999399 rgb/1311868169.999399.png 1311868170.014513 depth/1311868170.014513.png
1311868170.031274 rgb/1311868170.031274.png 1311868170.044946 depth/1311868170.044946.png
1311868170.063469 rgb/1311868170.063469.png 1311868170.076136 depth/1311868170.076136.png
1311868170.099394 rgb/1311868170.099394.png 1311868170.114660 depth/1311868170.114660.png
1311868170.131345 rgb/1311868170.131345.png 1311868170.144070 depth/1311868170.144070.png
1311868170.163416 rgb/1311868170.163416.png 1311868170.177624 depth/1311868170.177624.png
1311868170.199317 rgb/1311868170.199317.png 1311868170.213439 depth/1311868170.213439.png
1311868170.231467 rgb/1311868170.231467.png 1311868170.244916 depth/1311868170.244916.png
1311868170.263521 rgb/1311868170.263521.png 1311868170.276960 depth/1311868170.276960.png
1311868170.299432 rgb/1311868170.299432.png 1311868170.314762 depth/1311868170.314762.png
1311868170.331325 rgb/1311868170.331325.png 1311868170.344164 depth/1311868170.344164.png
1311868170.363400 rgb/1311868170.363400.png 1311868170.376729 depth/1311868170.376729.png
1311868170.399421 rgb/1311868170.399421.png 1311868170.413810 depth/1311868170.413810.png
1311868170.431288 rgb/1311868170.431288.png 1311868170.444929 depth/1311868170.444929.png
1311868170.463383 rgb/1311868170.463383.png 1311868170.476958 depth/1311868170.476958.png
1311868170.499476 rgb/1311868170.499476.png 1311868170.512513 depth/1311868170.512513.png
1311868170.531505 rgb/1311868170.531505.png 1311868170.546334 depth/1311868170.546334.png
1311868170.563345 rgb/1311868170.563345.png 1311868170.576738 depth/1311868170.576738.png
1311868170.599324 rgb/1311868170.599324.png 1311868170.614201 depth/1311868170.614201.png
1311868170.631485 rgb/1311868170.631485.png 1311868170.646250 depth/1311868170.646250.png
1311868170.663430 rgb/1311868170.663430.png 1311868170.678133 depth/1311868170.678133.png
1311868170.699432 rgb/1311868170.699432.png 1311868170.713182 depth/1311868170.713182.png
1311868170.731397 rgb/1311868170.731397.png 1311868170.745234 depth/1311868170.745234.png
1311868170.763453 rgb/1311868170.763453.png 1311868170.776288 depth/1311868170.776288.png
1311868170.799446 rgb/1311868170.799446.png 1311868170.814542 depth/1311868170.814542.png
1311868170.831309 rgb/1311868170.831309.png 1311868170.845482 depth/1311868170.845482.png
1311868170.863446 rgb/1311868170.863446.png 1311868170.877100 depth/1311868170.877100.png
1311868170.899435 rgb/1311868170.899435.png 1311868170.912926 depth/1311868170.912926.png
1311868170.931374 rgb/1311868170.931374.png 1311868170.945932 depth/1311868170.945932.png
1311868170.963440 rgb/1311868170.963440.png 1311868170.978389 depth/1311868170.978389.png
1311868170.999483 rgb/1311868170.999483.png 1311868171.012870 depth/1311868171.012870.png
1311868171.031493 rgb/1311868171.031493.png 1311868171.044724 depth/1311868171.044724.png
1311868171.063438 rgb/1311868171.063438.png 1311868171.081318 depth/1311868171.081318.png
1311868171.099448 rgb/1311868171.099448.png 1311868171.114152 depth/1311868171.114152.png
1311868171.131477 rgb/1311868171.131477.png 1311868171.145946 depth/1311868171.145946.png
1311868171.163447 rgb/1311868171.163447.png 1311868171.180214 depth/1311868171.180214.png
1311868171.199444 rgb/1311868171.199444.png 1311868171.214478 depth/1311868171.214478.png
1311868171.231391 rgb/1311868171.231391.png 1311868171.244574 depth/1311868171.244574.png
1311868171.263404 rgb/1311868171.263404.png 1311868171.281359 depth/1311868171.281359.png
1311868171.299368 rgb/1311868171.299368.png 1311868171.313542 depth/1311868171.313542.png
1311868171.331406 rgb/1311868171.331406.png 1311868171.345769 depth/1311868171.345769.png
1311868171.363479 rgb/1311868171.363479.png 1311868171.382663 depth/1311868171.382663.png
1311868171.399409 rgb/1311868171.399409.png 1311868171.413153 depth/1311868171.413153.png
1311868171.463459 rgb/1311868171.463459.png 1311868171.448332 depth/1311868171.448332.png
1311868171.499514 rgb/1311868171.499514.png 1311868171.514658 depth/1311868171.514658.png
1311868171.531471 rgb/1311868171.531471.png 1311868171.545883 depth/1311868171.545883.png
1311868171.563381 rgb/1311868171.563381.png 1311868171.580276 depth/1311868171.580276.png
1311868171.599490 rgb/1311868171.599490.png 1311868171.615486 depth/1311868171.615486.png
1311868171.631528 rgb/1311868171.631528.png 1311868171.644392 depth/1311868171.644392.png
1311868171.663411 rgb/1311868171.663411.png 1311868171.680537 depth/1311868171.680537.png
1311868171.699419 rgb/1311868171.699419.png 1311868171.712723 depth/1311868171.712723.png
1311868171.731499 rgb/1311868171.731499.png 1311868171.744488 depth/1311868171.744488.png
1311868171.763455 rgb/1311868171.763455.png 1311868171.780348 depth/1311868171.780348.png
1311868171.799464 rgb/1311868171.799464.png 1311868171.813158 depth/1311868171.813158.png
1311868171.831419 rgb/1311868171.831419.png 1311868171.845207 depth/1311868171.845207.png
1311868171.899575 rgb/1311868171.899575.png 1311868171.914819 depth/1311868171.914819.png
1311868171.931516 rgb/1311868171.931516.png 1311868171.945714 depth/1311868171.945714.png
1311868171.999580 rgb/1311868171.999580.png 1311868171.982100 depth/1311868171.982100.png
1311868172.031533 rgb/1311868172.031533.png 1311868172.016948 depth/1311868172.016948.png
1311868172.063426 rgb/1311868172.063426.png 1311868172.048421 depth/1311868172.048421.png
1311868172.099529 rgb/1311868172.099529.png 1311868172.113830 depth/1311868172.113830.png
1311868172.131546 rgb/1311868172.131546.png 1311868172.147015 depth/1311868172.147015.png
1311868172.163558 rgb/1311868172.163558.png 1311868172.181956 depth/1311868172.181956.png
1311868172.199781 rgb/1311868172.199781.png 1311868172.214983 depth/1311868172.214983.png
1311868172.263475 rgb/1311868172.263475.png 1311868172.248620 depth/1311868172.248620.png
1311868172.299544 rgb/1311868172.299544.png 1311868172.315192 depth/1311868172.315192.png
1311868172.363479 rgb/1311868172.363479.png 1311868172.350013 depth/1311868172.350013.png
1311868172.399483 rgb/1311868172.399483.png 1311868172.413939 depth/1311868172.413939.png
1311868172.463477 rgb/1311868172.463477.png 1311868172.449692 depth/1311868172.449692.png
1311868172.499467 rgb/1311868172.499467.png 1311868172.515495 depth/1311868172.515495.png
1311868172.563601 rgb/1311868172.563601.png 1311868172.549992 depth/1311868172.549992.png
1311868172.599590 rgb/1311868172.599590.png 1311868172.580944 depth/1311868172.580944.png
1311868172.631587 rgb/1311868172.631587.png 1311868172.615769 depth/1311868172.615769.png
1311868172.663612 rgb/1311868172.663612.png 1311868172.650102 depth/1311868172.650102.png
1311868172.699619 rgb/1311868172.699619.png 1311868172.713134 depth/1311868172.713134.png
1311868172.763469 rgb/1311868172.763469.png 1311868172.751196 depth/1311868172.751196.png
1311868172.799623 rgb/1311868172.799623.png 1311868172.815509 depth/1311868172.815509.png
1311868172.863483 rgb/1311868172.863483.png 1311868172.849287 depth/1311868172.849287.png
1311868172.899539 rgb/1311868172.899539.png 1311868172.882805 depth/1311868172.882805.png
1311868172.931607 rgb/1311868172.931607.png 1311868172.915927 depth/1311868172.915927.png
1311868172.963571 rgb/1311868172.963571.png 1311868172.950756 depth/1311868172.950756.png
1311868172.999602 rgb/1311868172.999602.png 1311868173.013773 depth/1311868173.013773.png
1311868173.067546 rgb/1311868173.067546.png 1311868173.050671 depth/1311868173.050671.png
1311868173.099605 rgb/1311868173.099605.png 1311868173.113327 depth/1311868173.113327.png
1311868173.131499 rgb/1311868173.131499.png 1311868173.149043 depth/1311868173.149043.png
1311868173.167457 rgb/1311868173.167457.png 1311868173.180971 depth/1311868173.180971.png
1311868173.199628 rgb/1311868173.199628.png 1311868173.213652 depth/1311868173.213652.png
1311868173.231487 rgb/1311868173.231487.png 1311868173.250386 depth/1311868173.250386.png
1311868173.267665 rgb/1311868173.267665.png 1311868173.283876 depth/1311868173.283876.png
1311868173.299659 rgb/1311868173.299659.png 1311868173.314048 depth/1311868173.314048.png
1311868173.331533 rgb/1311868173.331533.png 1311868173.349086 depth/1311868173.349086.png
1311868173.367650 rgb/1311868173.367650.png 1311868173.381642 depth/1311868173.381642.png
1311868173.399596 rgb/1311868173.399596.png 1311868173.414811 depth/1311868173.414811.png
1311868173.431624 rgb/1311868173.431624.png 1311868173.449252 depth/1311868173.449252.png
1311868173.467604 rgb/1311868173.467604.png 1311868173.483478 depth/1311868173.483478.png
1311868173.531628 rgb/1311868173.531628.png 1311868173.516984 depth/1311868173.516984.png
1311868173.567616 rgb/1311868173.567616.png 1311868173.581543 depth/1311868173.581543.png
1311868173.631603 rgb/1311868173.631603.png 1311868173.619855 depth/1311868173.619855.png
1311868173.667986 rgb/1311868173.667986.png 1311868173.654306 depth/1311868173.654306.png
1311868173.699670 rgb/1311868173.699670.png 1311868173.683641 depth/1311868173.683641.png
1311868173.731607 rgb/1311868173.731607.png 1311868173.717663 depth/1311868173.717663.png
1311868173.767623 rgb/1311868173.767623.png 1311868173.749076 depth/1311868173.749076.png
1311868173.799549 rgb/1311868173.799549.png 1311868173.784746 depth/1311868173.784746.png
1311868173.831620 rgb/1311868173.831620.png 1311868173.817750 depth/1311868173.817750.png
1311868173.867507 rgb/1311868173.867507.png 1311868173.882437 depth/1311868173.882437.png
1311868173.931642 rgb/1311868173.931642.png 1311868173.918618 depth/1311868173.918618.png
1311868173.967631 rgb/1311868173.967631.png 1311868173.950835 depth/1311868173.950835.png
1311868173.999745 rgb/1311868173.999745.png 1311868173.984224 depth/1311868173.984224.png
1311868174.031740 rgb/1311868174.031740.png 1311868174.017898 depth/1311868174.017898.png
1311868174.067656 rgb/1311868174.067656.png 1311868174.050437 depth/1311868174.050437.png
1311868174.099508 rgb/1311868174.099508.png 1311868174.084693 depth/1311868174.084693.png
1311868174.131747 rgb/1311868174.131747.png 1311868174.116996 depth/1311868174.116996.png
1311868174.167874 rgb/1311868174.167874.png 1311868174.182209 depth/1311868174.182209.png
1311868174.231617 rgb/1311868174.231617.png 1311868174.218679 depth/1311868174.218679.png
1311868174.267791 rgb/1311868174.267791.png 1311868174.250017 depth/1311868174.250017.png
1311868174.299749 rgb/1311868174.299749.png 1311868174.285697 depth/1311868174.285697.png
1311868174.331790 rgb/1311868174.331790.png 1311868174.317804 depth/1311868174.317804.png
1311868174.367988 rgb/1311868174.367988.png 1311868174.350271 depth/1311868174.350271.png
1311868174.399743 rgb/1311868174.399743.png 1311868174.386647 depth/1311868174.386647.png
1311868174.431786 rgb/1311868174.431786.png 1311868174.419476 depth/1311868174.419476.png
1311868174.467566 rgb/1311868174.467566.png 1311868174.452721 depth/1311868174.452721.png
1311868174.499672 rgb/1311868174.499672.png 1311868174.487772 depth/1311868174.487772.png
1311868174.531708 rgb/1311868174.531708.png 1311868174.518982 depth/1311868174.518982.png
1311868174.567585 rgb/1311868174.567585.png 1311868174.554621 depth/1311868174.554621.png
1311868174.599662 rgb/1311868174.599662.png 1311868174.584522 depth/1311868174.584522.png
1311868174.631772 rgb/1311868174.631772.png 1311868174.619814 depth/1311868174.619814.png
1311868174.667800 rgb/1311868174.667800.png 1311868174.651722 depth/1311868174.651722.png
1311868174.699578 rgb/1311868174.699578.png 1311868174.687374 depth/1311868174.687374.png
1311868174.731625 rgb/1311868174.731625.png 1311868174.719933 depth/1311868174.719933.png
1311868174.767680 rgb/1311868174.767680.png 1311868174.751101 depth/1311868174.751101.png
1311868174.799810 rgb/1311868174.799810.png 1311868174.789968 depth/1311868174.789968.png
1311868174.831815 rgb/1311868174.831815.png 1311868174.819171 depth/1311868174.819171.png
1311868174.867798 rgb/1311868174.867798.png 1311868174.849988 depth/1311868174.849988.png
1311868174.899678 rgb/1311868174.899678.png 1311868174.889132 depth/1311868174.889132.png
1311868174.931819 rgb/1311868174.931819.png 1311868174.917050 depth/1311868174.917050.png
1311868174.967694 rgb/1311868174.967694.png 1311868174.952141 depth/1311868174.952141.png
1311868174.999803 rgb/1311868174.999803.png 1311868174.988799 depth/1311868174.988799.png
1311868175.031665 rgb/1311868175.031665.png 1311868175.020776 depth/1311868175.020776.png
1311868175.067713 rgb/1311868175.067713.png 1311868175.048996 depth/1311868175.048996.png
1311868175.099631 rgb/1311868175.099631.png 1311868175.085546 depth/1311868175.085546.png
1311868175.131719 rgb/1311868175.131719.png 1311868175.118690 depth/1311868175.118690.png
1311868175.167807 rgb/1311868175.167807.png 1311868175.151936 depth/1311868175.151936.png
1311868175.199578 rgb/1311868175.199578.png 1311868175.187247 depth/1311868175.187247.png
1311868175.231818 rgb/1311868175.231818.png 1311868175.216686 depth/1311868175.216686.png
1311868175.267750 rgb/1311868175.267750.png 1311868175.254515 depth/1311868175.254515.png
1311868175.299978 rgb/1311868175.299978.png 1311868175.288057 depth/1311868175.288057.png
1311868175.331887 rgb/1311868175.331887.png 1311868175.320182 depth/1311868175.320182.png
1311868175.367738 rgb/1311868175.367738.png 1311868175.351161 depth/1311868175.351161.png
1311868175.400048 rgb/1311868175.400048.png 1311868175.387818 depth/1311868175.387818.png
1311868175.431994 rgb/1311868175.431994.png 1311868175.421391 depth/1311868175.421391.png
1311868175.467702 rgb/1311868175.467702.png 1311868175.449663 depth/1311868175.449663.png
1311868175.499770 rgb/1311868175.499770.png 1311868175.487565 depth/1311868175.487565.png
1311868175.531778 rgb/1311868175.531778.png 1311868175.519943 depth/1311868175.519943.png
1311868175.567800 rgb/1311868175.567800.png 1311868175.550912 depth/1311868175.550912.png
1311868175.599867 rgb/1311868175.599867.png 1311868175.587641 depth/1311868175.587641.png
1311868175.631778 rgb/1311868175.631778.png 1311868175.619756 depth/1311868175.619756.png
1311868175.667696 rgb/1311868175.667696.png 1311868175.649083 depth/1311868175.649083.png
1311868175.699784 rgb/1311868175.699784.png 1311868175.684710 depth/1311868175.684710.png
1311868175.731708 rgb/1311868175.731708.png 1311868175.719057 depth/1311868175.719057.png
1311868175.767584 rgb/1311868175.767584.png 1311868175.750556 depth/1311868175.750556.png
1311868175.799815 rgb/1311868175.799815.png 1311868175.788252 depth/1311868175.788252.png
1311868175.831761 rgb/1311868175.831761.png 1311868175.817245 depth/1311868175.817245.png
1311868175.867687 rgb/1311868175.867687.png 1311868175.850801 depth/1311868175.850801.png
1311868175.899663 rgb/1311868175.899663.png 1311868175.887345 depth/1311868175.887345.png
1311868175.931644 rgb/1311868175.931644.png 1311868175.917749 depth/1311868175.917749.png
1311868175.967871 rgb/1311868175.967871.png 1311868175.955575 depth/1311868175.955575.png
1311868175.999870 rgb/1311868175.999870.png 1311868175.988099 depth/1311868175.988099.png
1311868176.032043 rgb/1311868176.032043.png 1311868176.020287 depth/1311868176.020287.png
1311868176.067949 rgb/1311868176.067949.png 1311868176.055238 depth/1311868176.055238.png
1311868176.099801 rgb/1311868176.099801.png 1311868176.086530 depth/1311868176.086530.png
1311868176.131691 rgb/1311868176.131691.png 1311868176.119897 depth/1311868176.119897.png
1311868176.167963 rgb/1311868176.167963.png 1311868176.154293 depth/1311868176.154293.png
1311868176.199892 rgb/1311868176.199892.png 1311868176.188069 depth/1311868176.188069.png
1311868176.231937 rgb/1311868176.231937.png 1311868176.216891 depth/1311868176.216891.png
1311868176.267779 rgb/1311868176.267779.png 1311868176.254072 depth/1311868176.254072.png
1311868176.299834 rgb/1311868176.299834.png 1311868176.286843 depth/1311868176.286843.png
1311868176.331871 rgb/1311868176.331871.png 1311868176.319890 depth/1311868176.319890.png
1311868176.367752 rgb/1311868176.367752.png 1311868176.354614 depth/1311868176.354614.png
1311868176.399921 rgb/1311868176.399921.png 1311868176.384871 depth/1311868176.384871.png
1311868176.431678 rgb/1311868176.431678.png 1311868176.420020 depth/1311868176.420020.png
1311868176.467865 rgb/1311868176.467865.png 1311868176.457946 depth/1311868176.457946.png
1311868176.499760 rgb/1311868176.499760.png 1311868176.487950 depth/1311868176.487950.png
1311868176.531915 rgb/1311868176.531915.png 1311868176.519184 depth/1311868176.519184.png
1311868176.567758 rgb/1311868176.567758.png 1311868176.554180 depth/1311868176.554180.png
1311868176.602124 rgb/1311868176.602124.png 1311868176.588064 depth/1311868176.588064.png
1311868176.631719 rgb/1311868176.631719.png 1311868176.618839 depth/1311868176.618839.png
1311868176.667782 rgb/1311868176.667782.png 1311868176.655916 depth/1311868176.655916.png
1311868176.699787 rgb/1311868176.699787.png 1311868176.688107 depth/1311868176.688107.png
1311868176.731819 rgb/1311868176.731819.png 1311868176.718152 depth/1311868176.718152.png
1311868176.767814 rgb/1311868176.767814.png 1311868176.753106 depth/1311868176.753106.png
1311868176.799720 rgb/1311868176.799720.png 1311868176.787889 depth/1311868176.787889.png
1311868176.831887 rgb/1311868176.831887.png 1311868176.818027 depth/1311868176.818027.png
1311868176.867790 rgb/1311868176.867790.png 1311868176.854045 depth/1311868176.854045.png
1311868176.899837 rgb/1311868176.899837.png 1311868176.887985 depth/1311868176.887985.png
1311868176.931762 rgb/1311868176.931762.png 1311868176.917636 depth/1311868176.917636.png
1311868176.967856 rgb/1311868176.967856.png 1311868176.957238 depth/1311868176.957238.png
1311868176.999907 rgb/1311868176.999907.png 1311868176.988067 depth/1311868176.988067.png
1311868177.031966 rgb/1311868177.031966.png 1311868177.019840 depth/1311868177.019840.png
1311868177.067892 rgb/1311868177.067892.png 1311868177.053309 depth/1311868177.053309.png
1311868177.099730 rgb/1311868177.099730.png 1311868177.089594 depth/1311868177.089594.png
1311868177.131895 rgb/1311868177.131895.png 1311868177.117962 depth/1311868177.117962.png
1311868177.168091 rgb/1311868177.168091.png 1311868177.155926 depth/1311868177.155926.png
1311868177.199869 rgb/1311868177.199869.png 1311868177.188287 depth/1311868177.188287.png
1311868177.231903 rgb/1311868177.231903.png 1311868177.224759 depth/1311868177.224759.png
1311868177.267807 rgb/1311868177.267807.png 1311868177.255282 depth/1311868177.255282.png
1311868177.299871 rgb/1311868177.299871.png 1311868177.285963 depth/1311868177.285963.png
1311868177.331730 rgb/1311868177.331730.png 1311868177.322405 depth/1311868177.322405.png
1311868177.367900 rgb/1311868177.367900.png 1311868177.353213 depth/1311868177.353213.png
1311868177.399987 rgb/1311868177.399987.png 1311868177.387680 depth/1311868177.387680.png
1311868177.431827 rgb/1311868177.431827.png 1311868177.422370 depth/1311868177.422370.png
1311868177.467848 rgb/1311868177.467848.png 1311868177.454842 depth/1311868177.454842.png
1311868177.499762 rgb/1311868177.499762.png 1311868177.486612 depth/1311868177.486612.png
1311868177.531751 rgb/1311868177.531751.png 1311868177.521728 depth/1311868177.521728.png
1311868177.567851 rgb/1311868177.567851.png 1311868177.553540 depth/1311868177.553540.png
1311868177.599732 rgb/1311868177.599732.png 1311868177.588770 depth/1311868177.588770.png
1311868177.632083 rgb/1311868177.632083.png 1311868177.622670 depth/1311868177.622670.png
1311868177.667866 rgb/1311868177.667866.png 1311868177.654737 depth/1311868177.654737.png
1311868177.699913 rgb/1311868177.699913.png 1311868177.689225 depth/1311868177.689225.png
1311868177.731996 rgb/1311868177.731996.png 1311868177.722075 depth/1311868177.722075.png
1311868177.767937 rgb/1311868177.767937.png 1311868177.756389 depth/1311868177.756389.png
1311868177.799899 rgb/1311868177.799899.png 1311868177.785944 depth/1311868177.785944.png
1311868177.832005 rgb/1311868177.832005.png 1311868177.823182 depth/1311868177.823182.png
1311868177.867810 rgb/1311868177.867810.png 1311868177.853093 depth/1311868177.853093.png
1311868177.899856 rgb/1311868177.899856.png 1311868177.888965 depth/1311868177.888965.png
1311868177.931937 rgb/1311868177.931937.png 1311868177.922153 depth/1311868177.922153.png
1311868177.967919 rgb/1311868177.967919.png 1311868177.956515 depth/1311868177.956515.png
1311868178.000124 rgb/1311868178.000124.png 1311868177.988488 depth/1311868177.988488.png
1311868178.031988 rgb/1311868178.031988.png 1311868178.023893 depth/1311868178.023893.png
1311868178.068015 rgb/1311868178.068015.png 1311868178.056660 depth/1311868178.056660.png
1311868178.100039 rgb/1311868178.100039.png 1311868178.088612 depth/1311868178.088612.png
1311868178.131987 rgb/1311868178.131987.png 1311868178.123015 depth/1311868178.123015.png
1311868178.167955 rgb/1311868178.167955.png 1311868178.154939 depth/1311868178.154939.png
1311868178.199855 rgb/1311868178.199855.png 1311868178.188497 depth/1311868178.188497.png
1311868178.231966 rgb/1311868178.231966.png 1311868178.223125 depth/1311868178.223125.png
1311868178.267968 rgb/1311868178.267968.png 1311868178.256363 depth/1311868178.256363.png
1311868178.299815 rgb/1311868178.299815.png 1311868178.287054 depth/1311868178.287054.png
1311868178.332180 rgb/1311868178.332180.png 1311868178.326682 depth/1311868178.326682.png
1311868178.367989 rgb/1311868178.367989.png 1311868178.353561 depth/1311868178.353561.png
1311868178.400074 rgb/1311868178.400074.png 1311868178.388761 depth/1311868178.388761.png
1311868178.432167 rgb/1311868178.432167.png 1311868178.421230 depth/1311868178.421230.png
1311868178.467895 rgb/1311868178.467895.png 1311868178.454553 depth/1311868178.454553.png
1311868178.500102 rgb/1311868178.500102.png 1311868178.491175 depth/1311868178.491175.png
1311868178.531933 rgb/1311868178.531933.png 1311868178.521432 depth/1311868178.521432.png
1311868178.567928 rgb/1311868178.567928.png 1311868178.554561 depth/1311868178.554561.png
1311868178.600064 rgb/1311868178.600064.png 1311868178.593215 depth/1311868178.593215.png
1311868178.632030 rgb/1311868178.632030.png 1311868178.623597 depth/1311868178.623597.png
1311868178.668047 rgb/1311868178.668047.png 1311868178.654164 depth/1311868178.654164.png
1311868178.699917 rgb/1311868178.699917.png 1311868178.694880 depth/1311868178.694880.png
1311868178.731905 rgb/1311868178.731905.png 1311868178.721180 depth/1311868178.721180.png
1311868178.767938 rgb/1311868178.767938.png 1311868178.755005 depth/1311868178.755005.png
1311868178.799974 rgb/1311868178.799974.png 1311868178.789192 depth/1311868178.789192.png
1311868178.831967 rgb/1311868178.831967.png 1311868178.826203 depth/1311868178.826203.png
1311868178.867919 rgb/1311868178.867919.png 1311868178.855322 depth/1311868178.855322.png
1311868178.900038 rgb/1311868178.900038.png 1311868178.891570 depth/1311868178.891570.png
1311868178.932267 rgb/1311868178.932267.png 1311868178.926502 depth/1311868178.926502.png
1311868178.967934 rgb/1311868178.967934.png 1311868178.953383 depth/1311868178.953383.png
1311868179.000009 rgb/1311868179.000009.png 1311868178.991764 depth/1311868178.991764.png
1311868179.032182 rgb/1311868179.032182.png 1311868179.024394 depth/1311868179.024394.png
1311868179.067847 rgb/1311868179.067847.png 1311868179.054617 depth/1311868179.054617.png
1311868179.100093 rgb/1311868179.100093.png 1311868179.092608 depth/1311868179.092608.png
1311868179.132026 rgb/1311868179.132026.png 1311868179.123574 depth/1311868179.123574.png
1311868179.167985 rgb/1311868179.167985.png 1311868179.153903 depth/1311868179.153903.png
1311868179.200163 rgb/1311868179.200163.png 1311868179.191009 depth/1311868179.191009.png
1311868179.232011 rgb/1311868179.232011.png 1311868179.222802 depth/1311868179.222802.png
1311868179.268108 rgb/1311868179.268108.png 1311868179.253350 depth/1311868179.253350.png
1311868179.300467 rgb/1311868179.300467.png 1311868179.292764 depth/1311868179.292764.png
1311868179.333050 rgb/1311868179.333050.png 1311868179.324450 depth/1311868179.324450.png
1311868179.368133 rgb/1311868179.368133.png 1311868179.354206 depth/1311868179.354206.png
1311868179.400093 rgb/1311868179.400093.png 1311868179.392777 depth/1311868179.392777.png
1311868179.432203 rgb/1311868179.432203.png 1311868179.423985 depth/1311868179.423985.png
1311868179.467999 rgb/1311868179.467999.png 1311868179.458867 depth/1311868179.458867.png
1311868179.500080 rgb/1311868179.500080.png 1311868179.494098 depth/1311868179.494098.png
1311868179.532184 rgb/1311868179.532184.png 1311868179.523081 depth/1311868179.523081.png
1311868179.567958 rgb/1311868179.567958.png 1311868179.556083 depth/1311868179.556083.png
1311868179.600201 rgb/1311868179.600201.png 1311868179.594582 depth/1311868179.594582.png
1311868179.632001 rgb/1311868179.632001.png 1311868179.622672 depth/1311868179.622672.png
1311868179.668182 rgb/1311868179.668182.png 1311868179.659774 depth/1311868179.659774.png
1311868179.700151 rgb/1311868179.700151.png 1311868179.692799 depth/1311868179.692799.png
1311868179.732177 rgb/1311868179.732177.png 1311868179.722874 depth/1311868179.722874.png
1311868179.768285 rgb/1311868179.768285.png 1311868179.758585 depth/1311868179.758585.png
1311868179.800056 rgb/1311868179.800056.png 1311868179.790177 depth/1311868179.790177.png
1311868179.832089 rgb/1311868179.832089.png 1311868179.822815 depth/1311868179.822815.png
1311868179.867839 rgb/1311868179.867839.png 1311868179.857869 depth/1311868179.857869.png
1311868179.899932 rgb/1311868179.899932.png 1311868179.890505 depth/1311868179.890505.png
1311868179.932050 rgb/1311868179.932050.png 1311868179.921479 depth/1311868179.921479.png
1311868179.968012 rgb/1311868179.968012.png 1311868179.957179 depth/1311868179.957179.png
1311868179.999962 rgb/1311868179.999962.png 1311868179.989437 depth/1311868179.989437.png
1311868180.031945 rgb/1311868180.031945.png 1311868180.021938 depth/1311868180.021938.png
1311868180.068076 rgb/1311868180.068076.png 1311868180.057618 depth/1311868180.057618.png
1311868180.100092 rgb/1311868180.100092.png 1311868180.090030 depth/1311868180.090030.png
1311868180.131924 rgb/1311868180.131924.png 1311868180.121229 depth/1311868180.121229.png
1311868180.168096 rgb/1311868180.168096.png 1311868180.157172 depth/1311868180.157172.png
1311868180.200023 rgb/1311868180.200023.png 1311868180.190922 depth/1311868180.190922.png
1311868180.232155 rgb/1311868180.232155.png 1311868180.221475 depth/1311868180.221475.png
1311868180.268004 rgb/1311868180.268004.png 1311868180.257830 depth/1311868180.257830.png
1311868180.299978 rgb/1311868180.299978.png 1311868180.289335 depth/1311868180.289335.png
1311868180.331912 rgb/1311868180.331912.png 1311868180.321483 depth/1311868180.321483.png
1311868180.368101 rgb/1311868180.368101.png 1311868180.357148 depth/1311868180.357148.png
1311868180.400081 rgb/1311868180.400081.png 1311868180.389488 depth/1311868180.389488.png
1311868180.432000 rgb/1311868180.432000.png 1311868180.421520 depth/1311868180.421520.png
1311868180.468133 rgb/1311868180.468133.png 1311868180.457275 depth/1311868180.457275.png
1311868180.500082 rgb/1311868180.500082.png 1311868180.489377 depth/1311868180.489377.png
1311868180.531936 rgb/1311868180.531936.png 1311868180.521462 depth/1311868180.521462.png
1311868180.568027 rgb/1311868180.568027.png 1311868180.557221 depth/1311868180.557221.png
1311868180.600047 rgb/1311868180.600047.png 1311868180.590522 depth/1311868180.590522.png
1311868180.632105 rgb/1311868180.632105.png 1311868180.621305 depth/1311868180.621305.png
1311868180.668185 rgb/1311868180.668185.png 1311868180.658623 depth/1311868180.658623.png
1311868180.700174 rgb/1311868180.700174.png 1311868180.690541 depth/1311868180.690541.png
1311868180.732090 rgb/1311868180.732090.png 1311868180.722995 depth/1311868180.722995.png
1311868180.768172 rgb/1311868180.768172.png 1311868180.758766 depth/1311868180.758766.png
1311868180.800199 rgb/1311868180.800199.png 1311868180.792653 depth/1311868180.792653.png
1311868180.832010 rgb/1311868180.832010.png 1311868180.822029 depth/1311868180.822029.png
1311868180.867980 rgb/1311868180.867980.png 1311868180.857260 depth/1311868180.857260.png
1311868180.899974 rgb/1311868180.899974.png 1311868180.889509 depth/1311868180.889509.png
1311868180.932135 rgb/1311868180.932135.png 1311868180.925219 depth/1311868180.925219.png
1311868180.968026 rgb/1311868180.968026.png 1311868180.957367 depth/1311868180.957367.png
1311868181.000013 rgb/1311868181.000013.png 1311868180.989517 depth/1311868180.989517.png
1311868181.032168 rgb/1311868181.032168.png 1311868181.025444 depth/1311868181.025444.png
1311868181.068183 rgb/1311868181.068183.png 1311868181.059147 depth/1311868181.059147.png
1311868181.100120 rgb/1311868181.100120.png 1311868181.090930 depth/1311868181.090930.png
1311868181.132035 rgb/1311868181.132035.png 1311868181.125471 depth/1311868181.125471.png
1311868181.168020 rgb/1311868181.168020.png 1311868181.157365 depth/1311868181.157365.png
1311868181.200040 rgb/1311868181.200040.png 1311868181.189422 depth/1311868181.189422.png
1311868181.232080 rgb/1311868181.232080.png 1311868181.225265 depth/1311868181.225265.png
1311868181.268006 rgb/1311868181.268006.png 1311868181.257693 depth/1311868181.257693.png
1311868181.300111 rgb/1311868181.300111.png 1311868181.290158 depth/1311868181.290158.png
1311868181.332051 rgb/1311868181.332051.png 1311868181.325603 depth/1311868181.325603.png
1311868181.367997 rgb/1311868181.367997.png 1311868181.357529 depth/1311868181.357529.png
1311868181.400094 rgb/1311868181.400094.png 1311868181.390080 depth/1311868181.390080.png
1311868181.432419 rgb/1311868181.432419.png 1311868181.427528 depth/1311868181.427528.png
1311868181.468024 rgb/1311868181.468024.png 1311868181.457676 depth/1311868181.457676.png
1311868181.500288 rgb/1311868181.500288.png 1311868181.490154 depth/1311868181.490154.png
1311868181.532183 rgb/1311868181.532183.png 1311868181.526157 depth/1311868181.526157.png
1311868181.568153 rgb/1311868181.568153.png 1311868181.560894 depth/1311868181.560894.png
1311868181.600115 rgb/1311868181.600115.png 1311868181.590195 depth/1311868181.590195.png
1311868181.632435 rgb/1311868181.632435.png 1311868181.625858 depth/1311868181.625858.png
1311868181.668011 rgb/1311868181.668011.png 1311868181.657364 depth/1311868181.657364.png
1311868181.700024 rgb/1311868181.700024.png 1311868181.689655 depth/1311868181.689655.png
1311868181.732563 rgb/1311868181.732563.png 1311868181.725345 depth/1311868181.725345.png
1311868181.768063 rgb/1311868181.768063.png 1311868181.758495 depth/1311868181.758495.png
1311868181.800057 rgb/1311868181.800057.png 1311868181.790125 depth/1311868181.790125.png
1311868181.832157 rgb/1311868181.832157.png 1311868181.825364 depth/1311868181.825364.png
1311868181.868146 rgb/1311868181.868146.png 1311868181.857557 depth/1311868181.857557.png
1311868181.900215 rgb/1311868181.900215.png 1311868181.892701 depth/1311868181.892701.png
1311868181.932068 rgb/1311868181.932068.png 1311868181.925316 depth/1311868181.925316.png
1311868181.968208 rgb/1311868181.968208.png 1311868181.959762 depth/1311868181.959762.png
1311868182.000232 rgb/1311868182.000232.png 1311868181.992505 depth/1311868181.992505.png
1311868182.032194 rgb/1311868182.032194.png 1311868182.027831 depth/1311868182.027831.png
1311868182.068176 rgb/1311868182.068176.png 1311868182.057492 depth/1311868182.057492.png
1311868182.100226 rgb/1311868182.100226.png 1311868182.090848 depth/1311868182.090848.png
1311868182.136196 rgb/1311868182.136196.png 1311868182.125663 depth/1311868182.125663.png
1311868182.168077 rgb/1311868182.168077.png 1311868182.158087 depth/1311868182.158087.png
1311868182.200278 rgb/1311868182.200278.png 1311868182.193465 depth/1311868182.193465.png
1311868182.236167 rgb/1311868182.236167.png 1311868182.227644 depth/1311868182.227644.png
1311868182.268066 rgb/1311868182.268066.png 1311868182.257557 depth/1311868182.257557.png
1311868182.300234 rgb/1311868182.300234.png 1311868182.293645 depth/1311868182.293645.png
1311868182.336153 rgb/1311868182.336153.png 1311868182.325330 depth/1311868182.325330.png
1311868182.368183 rgb/1311868182.368183.png 1311868182.360580 depth/1311868182.360580.png
1311868182.400284 rgb/1311868182.400284.png 1311868182.393420 depth/1311868182.393420.png
1311868182.436053 rgb/1311868182.436053.png 1311868182.425586 depth/1311868182.425586.png
1311868182.468090 rgb/1311868182.468090.png 1311868182.459061 depth/1311868182.459061.png
1311868182.500921 rgb/1311868182.500921.png 1311868182.496222 depth/1311868182.496222.png
1311868182.536127 rgb/1311868182.536127.png 1311868182.525833 depth/1311868182.525833.png
1311868182.568033 rgb/1311868182.568033.png 1311868182.557951 depth/1311868182.557951.png
1311868182.600295 rgb/1311868182.600295.png 1311868182.593603 depth/1311868182.593603.png
1311868182.636312 rgb/1311868182.636312.png 1311868182.625359 depth/1311868182.625359.png
1311868182.668039 rgb/1311868182.668039.png 1311868182.657654 depth/1311868182.657654.png
1311868182.700341 rgb/1311868182.700341.png 1311868182.693647 depth/1311868182.693647.png
1311868182.736220 rgb/1311868182.736220.png 1311868182.726508 depth/1311868182.726508.png
1311868182.768253 rgb/1311868182.768253.png 1311868182.759036 depth/1311868182.759036.png
1311868182.800181 rgb/1311868182.800181.png 1311868182.796353 depth/1311868182.796353.png
1311868182.836155 rgb/1311868182.836155.png 1311868182.825316 depth/1311868182.825316.png
1311868182.868215 rgb/1311868182.868215.png 1311868182.857765 depth/1311868182.857765.png
1311868182.900229 rgb/1311868182.900229.png 1311868182.895733 depth/1311868182.895733.png
1311868182.936274 rgb/1311868182.936274.png 1311868182.925415 depth/1311868182.925415.png
1311868182.968092 rgb/1311868182.968092.png 1311868182.958230 depth/1311868182.958230.png
1311868183.000259 rgb/1311868183.000259.png 1311868182.994413 depth/1311868182.994413.png
1311868183.036254 rgb/1311868183.036254.png 1311868183.028182 depth/1311868183.028182.png
1311868183.068333 rgb/1311868183.068333.png 1311868183.059929 depth/1311868183.059929.png
1311868183.100611 rgb/1311868183.100611.png 1311868183.094902 depth/1311868183.094902.png
1311868183.136176 rgb/1311868183.136176.png 1311868183.125358 depth/1311868183.125358.png
1311868183.168211 rgb/1311868183.168211.png 1311868183.158526 depth/1311868183.158526.png
1311868183.200276 rgb/1311868183.200276.png 1311868183.193940 depth/1311868183.193940.png
1311868183.236295 rgb/1311868183.236295.png 1311868183.226777 depth/1311868183.226777.png
1311868183.268380 rgb/1311868183.268380.png 1311868183.258677 depth/1311868183.258677.png
1311868183.300363 rgb/1311868183.300363.png 1311868183.294638 depth/1311868183.294638.png
1311868183.336308 rgb/1311868183.336308.png 1311868183.325625 depth/1311868183.325625.png
1311868183.368469 rgb/1311868183.368469.png 1311868183.362204 depth/1311868183.362204.png
1311868183.400232 rgb/1311868183.400232.png 1311868183.393435 depth/1311868183.393435.png
1311868183.436153 rgb/1311868183.436153.png 1311868183.427013 depth/1311868183.427013.png
1311868183.468217 rgb/1311868183.468217.png 1311868183.462872 depth/1311868183.462872.png
1311868183.500255 rgb/1311868183.500255.png 1311868183.494510 depth/1311868183.494510.png
1311868183.536275 rgb/1311868183.536275.png 1311868183.526761 depth/1311868183.526761.png
1311868183.568369 rgb/1311868183.568369.png 1311868183.561686 depth/1311868183.561686.png
1311868183.600217 rgb/1311868183.600217.png 1311868183.593533 depth/1311868183.593533.png
1311868183.636216 rgb/1311868183.636216.png 1311868183.626579 depth/1311868183.626579.png
1311868183.668587 rgb/1311868183.668587.png 1311868183.663689 depth/1311868183.663689.png
1311868183.700230 rgb/1311868183.700230.png 1311868183.693292 depth/1311868183.693292.png
1311868183.736414 rgb/1311868183.736414.png 1311868183.725733 depth/1311868183.725733.png
1311868183.768221 rgb/1311868183.768221.png 1311868183.762136 depth/1311868183.762136.png
1311868183.800370 rgb/1311868183.800370.png 1311868183.793340 depth/1311868183.793340.png
1311868183.836230 rgb/1311868183.836230.png 1311868183.825722 depth/1311868183.825722.png
1311868183.868506 rgb/1311868183.868506.png 1311868183.861495 depth/1311868183.861495.png
1311868183.900249 rgb/1311868183.900249.png 1311868183.895185 depth/1311868183.895185.png
1311868183.936316 rgb/1311868183.936316.png 1311868183.925453 depth/1311868183.925453.png
1311868183.968498 rgb/1311868183.968498.png 1311868183.964203 depth/1311868183.964203.png
1311868184.000440 rgb/1311868184.000440.png 1311868183.998854 depth/1311868183.998854.png
1311868184.036316 rgb/1311868184.036316.png 1311868184.029638 depth/1311868184.029638.png
1311868184.070267 rgb/1311868184.070267.png 1311868184.065428 depth/1311868184.065428.png
1311868184.100684 rgb/1311868184.100684.png 1311868184.097360 depth/1311868184.097360.png
1311868184.136827 rgb/1311868184.136827.png 1311868184.131161 depth/1311868184.131161.png
1311868184.169015 rgb/1311868184.169015.png 1311868184.164337 depth/1311868184.164337.png
1311868184.200464 rgb/1311868184.200464.png 1311868184.194772 depth/1311868184.194772.png
1311868184.236434 rgb/1311868184.236434.png 1311868184.227431 depth/1311868184.227431.png
1311868184.268504 rgb/1311868184.268504.png 1311868184.265642 depth/1311868184.265642.png
1311868184.300643 rgb/1311868184.300643.png 1311868184.294755 depth/1311868184.294755.png
1311868184.336293 rgb/1311868184.336293.png 1311868184.325312 depth/1311868184.325312.png
1311868184.368210 rgb/1311868184.368210.png 1311868184.366284 depth/1311868184.366284.png
1311868184.400303 rgb/1311868184.400303.png 1311868184.393954 depth/1311868184.393954.png
1311868184.436272 rgb/1311868184.436272.png 1311868184.426497 depth/1311868184.426497.png
1311868184.468412 rgb/1311868184.468412.png 1311868184.464418 depth/1311868184.464418.png
1311868184.500438 rgb/1311868184.500438.png 1311868184.497646 depth/1311868184.497646.png
1311868184.536326 rgb/1311868184.536326.png 1311868184.528277 depth/1311868184.528277.png
1311868184.568437 rgb/1311868184.568437.png 1311868184.561422 depth/1311868184.561422.png
1311868184.600381 rgb/1311868184.600381.png 1311868184.594532 depth/1311868184.594532.png
1311868184.636350 rgb/1311868184.636350.png 1311868184.632774 depth/1311868184.632774.png
1311868184.668352 rgb/1311868184.668352.png 1311868184.664162 depth/1311868184.664162.png
1311868184.700710 rgb/1311868184.700710.png 1311868184.693635 depth/1311868184.693635.png
1311868184.736501 rgb/1311868184.736501.png 1311868184.731115 depth/1311868184.731115.png
1311868184.768456 rgb/1311868184.768456.png 1311868184.762298 depth/1311868184.762298.png
1311868184.800366 rgb/1311868184.800366.png 1311868184.796163 depth/1311868184.796163.png
1311868184.836324 rgb/1311868184.836324.png 1311868184.833854 depth/1311868184.833854.png
1311868184.868735 rgb/1311868184.868735.png 1311868184.863723 depth/1311868184.863723.png
1311868184.900445 rgb/1311868184.900445.png 1311868184.894504 depth/1311868184.894504.png
1311868184.936308 rgb/1311868184.936308.png 1311868184.929521 depth/1311868184.929521.png
1311868184.968436 rgb/1311868184.968436.png 1311868184.964801 depth/1311868184.964801.png
1311868185.000422 rgb/1311868185.000422.png 1311868184.997771 depth/1311868184.997771.png
1311868185.036432 rgb/1311868185.036432.png 1311868185.032688 depth/1311868185.032688.png
1311868185.068440 rgb/1311868185.068440.png 1311868185.065252 depth/1311868185.065252.png
1311868185.100898 rgb/1311868185.100898.png 1311868185.094927 depth/1311868185.094927.png
1311868185.136538 rgb/1311868185.136538.png 1311868185.131256 depth/1311868185.131256.png
1311868185.168559 rgb/1311868185.168559.png 1311868185.163261 depth/1311868185.163261.png
1311868185.200754 rgb/1311868185.200754.png 1311868185.195260 depth/1311868185.195260.png
1311868185.236390 rgb/1311868185.236390.png 1311868185.230718 depth/1311868185.230718.png
1311868185.268543 rgb/1311868185.268543.png 1311868185.261566 depth/1311868185.261566.png
1311868185.300484 rgb/1311868185.300484.png 1311868185.295784 depth/1311868185.295784.png
1311868185.337903 rgb/1311868185.337903.png 1311868185.330870 depth/1311868185.330870.png
1311868185.368510 rgb/1311868185.368510.png 1311868185.365297 depth/1311868185.365297.png
1311868185.401199 rgb/1311868185.401199.png 1311868185.395355 depth/1311868185.395355.png
1311868185.436438 rgb/1311868185.436438.png 1311868185.430442 depth/1311868185.430442.png
1311868185.468575 rgb/1311868185.468575.png 1311868185.462286 depth/1311868185.462286.png
1311868185.500443 rgb/1311868185.500443.png 1311868185.498438 depth/1311868185.498438.png
1311868185.536414 rgb/1311868185.536414.png 1311868185.529876 depth/1311868185.529876.png
1311868185.568460 rgb/1311868185.568460.png 1311868185.561420 depth/1311868185.561420.png
1311868185.600364 rgb/1311868185.600364.png 1311868185.593407 depth/1311868185.593407.png
1311868185.636409 rgb/1311868185.636409.png 1311868185.631497 depth/1311868185.631497.png
1311868185.668624 rgb/1311868185.668624.png 1311868185.664412 depth/1311868185.664412.png
1311868185.701972 rgb/1311868185.701972.png 1311868185.696702 depth/1311868185.696702.png
1311868185.736700 rgb/1311868185.736700.png 1311868185.729373 depth/1311868185.729373.png
1311868185.768630 rgb/1311868185.768630.png 1311868185.761504 depth/1311868185.761504.png
1311868185.800441 rgb/1311868185.800441.png 1311868185.797812 depth/1311868185.797812.png
1311868185.836824 rgb/1311868185.836824.png 1311868185.831964 depth/1311868185.831964.png
1311868185.868447 rgb/1311868185.868447.png 1311868185.865112 depth/1311868185.865112.png
1311868185.900384 rgb/1311868185.900384.png 1311868185.900213 depth/1311868185.900213.png
1311868185.936471 rgb/1311868185.936471.png 1311868185.930809 depth/1311868185.930809.png
1311868185.968391 rgb/1311868185.968391.png 1311868185.962781 depth/1311868185.962781.png
1311868186.000413 rgb/1311868186.000413.png 1311868186.000459 depth/1311868186.000459.png
1311868186.036453 rgb/1311868186.036453.png 1311868186.029395 depth/1311868186.029395.png
1311868186.068672 rgb/1311868186.068672.png 1311868186.062642 depth/1311868186.062642.png
1311868186.103248 rgb/1311868186.103248.png 1311868186.103255 depth/1311868186.103255.png
1311868186.136633 rgb/1311868186.136633.png 1311868186.131039 depth/1311868186.131039.png
1311868186.168524 rgb/1311868186.168524.png 1311868186.162711 depth/1311868186.162711.png
1311868186.200391 rgb/1311868186.200391.png 1311868186.198710 depth/1311868186.198710.png
1311868186.237659 rgb/1311868186.237659.png 1311868186.231643 depth/1311868186.231643.png
1311868186.268650 rgb/1311868186.268650.png 1311868186.263250 depth/1311868186.263250.png
1311868186.300401 rgb/1311868186.300401.png 1311868186.297487 depth/1311868186.297487.png
1311868186.336402 rgb/1311868186.336402.png 1311868186.332293 depth/1311868186.332293.png
1311868186.368410 rgb/1311868186.368410.png 1311868186.364448 depth/1311868186.364448.png
1311868186.400544 rgb/1311868186.400544.png 1311868186.400205 depth/1311868186.400205.png
1311868186.436523 rgb/1311868186.436523.png 1311868186.431456 depth/1311868186.431456.png
1311868186.468526 rgb/1311868186.468526.png 1311868186.465585 depth/1311868186.465585.png
1311868186.500490 rgb/1311868186.500490.png 1311868186.498497 depth/1311868186.498497.png
1311868186.537052 rgb/1311868186.537052.png 1311868186.529775 depth/1311868186.529775.png
1311868186.568549 rgb/1311868186.568549.png 1311868186.565656 depth/1311868186.565656.png
1311868186.600576 rgb/1311868186.600576.png 1311868186.597659 depth/1311868186.597659.png
1311868186.636497 rgb/1311868186.636497.png 1311868186.632110 depth/1311868186.632110.png
1311868186.668623 rgb/1311868186.668623.png 1311868186.665093 depth/1311868186.665093.png
1311868186.702517 rgb/1311868186.702517.png 1311868186.702525 depth/1311868186.702525.png
1311868186.736720 rgb/1311868186.736720.png 1311868186.730707 depth/1311868186.730707.png
1311868186.768504 rgb/1311868186.768504.png 1311868186.764423 depth/1311868186.764423.png
1311868186.800524 rgb/1311868186.800524.png 1311868186.799103 depth/1311868186.799103.png
1311868186.836721 rgb/1311868186.836721.png 1311868186.832462 depth/1311868186.832462.png
1311868186.869317 rgb/1311868186.869317.png 1311868186.867740 depth/1311868186.867740.png
1311868186.900515 rgb/1311868186.900515.png 1311868186.900525 depth/1311868186.900525.png
1311868186.936400 rgb/1311868186.936400.png 1311868186.930682 depth/1311868186.930682.png
1311868186.968636 rgb/1311868186.968636.png 1311868186.963995 depth/1311868186.963995.png
1311868187.000505 rgb/1311868187.000505.png 1311868186.997592 depth/1311868186.997592.png
1311868187.036707 rgb/1311868187.036707.png 1311868187.032681 depth/1311868187.032681.png
1311868187.068458 rgb/1311868187.068458.png 1311868187.068252 depth/1311868187.068252.png
1311868187.101696 rgb/1311868187.101696.png 1311868187.101780 depth/1311868187.101780.png
1311868187.136587 rgb/1311868187.136587.png 1311868187.129856 depth/1311868187.129856.png
1311868187.169000 rgb/1311868187.169000.png 1311868187.169019 depth/1311868187.169019.png
1311868187.201269 rgb/1311868187.201269.png 1311868187.201451 depth/1311868187.201451.png
1311868187.236433 rgb/1311868187.236433.png 1311868187.229725 depth/1311868187.229725.png
1311868187.268822 rgb/1311868187.268822.png 1311868187.267911 depth/1311868187.267911.png
1311868187.300515 rgb/1311868187.300515.png 1311868187.297598 depth/1311868187.297598.png
1311868187.336611 rgb/1311868187.336611.png 1311868187.329539 depth/1311868187.329539.png
1311868187.368415 rgb/1311868187.368415.png 1311868187.366889 depth/1311868187.366889.png
1311868187.400493 rgb/1311868187.400493.png 1311868187.398190 depth/1311868187.398190.png
1311868187.436706 rgb/1311868187.436706.png 1311868187.429671 depth/1311868187.429671.png
1311868187.468568 rgb/1311868187.468568.png 1311868187.466043 depth/1311868187.466043.png
1311868187.500548 rgb/1311868187.500548.png 1311868187.499103 depth/1311868187.499103.png
1311868187.537564 rgb/1311868187.537564.png 1311868187.533630 depth/1311868187.533630.png
1311868187.568523 rgb/1311868187.568523.png 1311868187.567265 depth/1311868187.567265.png
1311868187.600502 rgb/1311868187.600502.png 1311868187.599855 depth/1311868187.599855.png
1311868187.636477 rgb/1311868187.636477.png 1311868187.630800 depth/1311868187.630800.png
1311868187.668730 rgb/1311868187.668730.png 1311868187.668744 depth/1311868187.668744.png
1311868187.700555 rgb/1311868187.700555.png 1311868187.702510 depth/1311868187.702510.png
1311868187.736522 rgb/1311868187.736522.png 1311868187.730639 depth/1311868187.730639.png
1311868187.768746 rgb/1311868187.768746.png 1311868187.765606 depth/1311868187.765606.png
1311868187.800538 rgb/1311868187.800538.png 1311868187.797602 depth/1311868187.797602.png
1311868187.837466 rgb/1311868187.837466.png 1311868187.831569 depth/1311868187.831569.png
1311868187.868577 rgb/1311868187.868577.png 1311868187.868610 depth/1311868187.868610.png
1311868187.900542 rgb/1311868187.900542.png 1311868187.897895 depth/1311868187.897895.png
1311868187.936595 rgb/1311868187.936595.png 1311868187.930750 depth/1311868187.930750.png
1311868187.968459 rgb/1311868187.968459.png 1311868187.965630 depth/1311868187.965630.png
1311868188.000735 rgb/1311868188.000735.png 1311868187.999806 depth/1311868187.999806.png
1311868188.036686 rgb/1311868188.036686.png 1311868188.032674 depth/1311868188.032674.png
1311868188.068520 rgb/1311868188.068520.png 1311868188.065787 depth/1311868188.065787.png
1311868188.100428 rgb/1311868188.100428.png 1311868188.099538 depth/1311868188.099538.png
1311868188.136705 rgb/1311868188.136705.png 1311868188.129752 depth/1311868188.129752.png
1311868188.169752 rgb/1311868188.169752.png 1311868188.169761 depth/1311868188.169761.png
1311868188.200610 rgb/1311868188.200610.png 1311868188.198653 depth/1311868188.198653.png
1311868188.236529 rgb/1311868188.236529.png 1311868188.231993 depth/1311868188.231993.png
1311868188.268577 rgb/1311868188.268577.png 1311868188.268589 depth/1311868188.268589.png
1311868188.300900 rgb/1311868188.300900.png 1311868188.300915 depth/1311868188.300915.png
1311868188.336811 rgb/1311868188.336811.png 1311868188.336856 depth/1311868188.336856.png
1311868188.368537 rgb/1311868188.368537.png 1311868188.368551 depth/1311868188.368551.png
1311868188.400512 rgb/1311868188.400512.png 1311868188.397902 depth/1311868188.397902.png
1311868188.437067 rgb/1311868188.437067.png 1311868188.437076 depth/1311868188.437076.png
1311868188.468574 rgb/1311868188.468574.png 1311868188.466426 depth/1311868188.466426.png
1311868188.502489 rgb/1311868188.502489.png 1311868188.502757 depth/1311868188.502757.png
1311868188.537539 rgb/1311868188.537539.png 1311868188.537698 depth/1311868188.537698.png
1311868188.568686 rgb/1311868188.568686.png 1311868188.565863 depth/1311868188.565863.png
1311868188.601444 rgb/1311868188.601444.png 1311868188.601456 depth/1311868188.601456.png
1311868188.637504 rgb/1311868188.637504.png 1311868188.637522 depth/1311868188.637522.png
1311868188.668666 rgb/1311868188.668666.png 1311868188.666127 depth/1311868188.666127.png
1311868188.703460 rgb/1311868188.703460.png 1311868188.698743 depth/1311868188.698743.png
1311868188.736639 rgb/1311868188.736639.png 1311868188.736650 depth/1311868188.736650.png
1311868188.768663 rgb/1311868188.768663.png 1311868188.766731 depth/1311868188.766731.png
1311868188.800670 rgb/1311868188.800670.png 1311868188.799224 depth/1311868188.799224.png
1311868188.836521 rgb/1311868188.836521.png 1311868188.834136 depth/1311868188.834136.png
1311868188.868469 rgb/1311868188.868469.png 1311868188.868490 depth/1311868188.868490.png
1311868188.900697 rgb/1311868188.900697.png 1311868188.897980 depth/1311868188.897980.png
1311868188.936521 rgb/1311868188.936521.png 1311868188.936530 depth/1311868188.936530.png
1311868188.968696 rgb/1311868188.968696.png 1311868188.965787 depth/1311868188.965787.png
1311868189.000574 rgb/1311868189.000574.png 1311868188.998315 depth/1311868188.998315.png
1311868189.036870 rgb/1311868189.036870.png 1311868189.042396 depth/1311868189.042396.png
1311868189.068620 rgb/1311868189.068620.png 1311868189.067516 depth/1311868189.067516.png
1311868189.100649 rgb/1311868189.100649.png 1311868189.097816 depth/1311868189.097816.png
1311868189.136620 rgb/1311868189.136620.png 1311868189.136023 depth/1311868189.136023.png
1311868189.168589 rgb/1311868189.168589.png 1311868189.167471 depth/1311868189.167471.png
1311868189.201174 rgb/1311868189.201174.png 1311868189.198871 depth/1311868189.198871.png
1311868189.238292 rgb/1311868189.238292.png 1311868189.244009 depth/1311868189.244009.png
1311868189.268669 rgb/1311868189.268669.png 1311868189.266412 depth/1311868189.266412.png
1311868189.302276 rgb/1311868189.302276.png 1311868189.302764 depth/1311868189.302764.png
1311868189.337870 rgb/1311868189.337870.png 1311868189.335967 depth/1311868189.335967.png
1311868189.368446 rgb/1311868189.368446.png 1311868189.367497 depth/1311868189.367497.png
1311868189.400547 rgb/1311868189.400547.png 1311868189.398091 depth/1311868189.398091.png
1311868189.436651 rgb/1311868189.436651.png 1311868189.433995 depth/1311868189.433995.png
1311868189.468797 rgb/1311868189.468797.png 1311868189.468848 depth/1311868189.468848.png
1311868189.500573 rgb/1311868189.500573.png 1311868189.499832 depth/1311868189.499832.png
1311868189.536633 rgb/1311868189.536633.png 1311868189.535532 depth/1311868189.535532.png
1311868189.568724 rgb/1311868189.568724.png 1311868189.566072 depth/1311868189.566072.png
1311868189.601920 rgb/1311868189.601920.png 1311868189.601927 depth/1311868189.601927.png
1311868189.636729 rgb/1311868189.636729.png 1311868189.636736 depth/1311868189.636736.png
1311868189.668663 rgb/1311868189.668663.png 1311868189.666056 depth/1311868189.666056.png
1311868189.704376 rgb/1311868189.704376.png 1311868189.704390 depth/1311868189.704390.png
1311868189.736593 rgb/1311868189.736593.png 1311868189.733822 depth/1311868189.733822.png
1311868189.768868 rgb/1311868189.768868.png 1311868189.765987 depth/1311868189.765987.png
1311868189.802939 rgb/1311868189.802939.png 1311868189.802943 depth/1311868189.802943.png
1311868189.836562 rgb/1311868189.836562.png 1311868189.835567 depth/1311868189.835567.png
1311868189.868685 rgb/1311868189.868685.png 1311868189.865810 depth/1311868189.865810.png
1311868189.902037 rgb/1311868189.902037.png 1311868189.902057 depth/1311868189.902057.png
1311868189.936714 rgb/1311868189.936714.png 1311868189.934126 depth/1311868189.934126.png
1311868189.968616 rgb/1311868189.968616.png 1311868189.966738 depth/1311868189.966738.png
1311868190.002005 rgb/1311868190.002005.png 1311868190.002015 depth/1311868190.002015.png
1311868190.036745 rgb/1311868190.036745.png 1311868190.033893 depth/1311868190.033893.png
1311868190.068604 rgb/1311868190.068604.png 1311868190.065911 depth/1311868190.065911.png
1311868190.104099 rgb/1311868190.104099.png 1311868190.104109 depth/1311868190.104109.png
1311868190.136685 rgb/1311868190.136685.png 1311868190.133886 depth/1311868190.133886.png
1311868190.168751 rgb/1311868190.168751.png 1311868190.166060 depth/1311868190.166060.png
1311868190.202446 rgb/1311868190.202446.png 1311868190.202456 depth/1311868190.202456.png
1311868190.236836 rgb/1311868190.236836.png 1311868190.233912 depth/1311868190.233912.png
1311868190.268616 rgb/1311868190.268616.png 1311868190.268216 depth/1311868190.268216.png
1311868190.302512 rgb/1311868190.302512.png 1311868190.302524 depth/1311868190.302524.png
1311868190.336668 rgb/1311868190.336668.png 1311868190.334219 depth/1311868190.334219.png
1311868190.369230 rgb/1311868190.369230.png 1311868190.366015 depth/1311868190.366015.png
1311868190.401976 rgb/1311868190.401976.png 1311868190.401989 depth/1311868190.401989.png
1311868190.436649 rgb/1311868190.436649.png 1311868190.433995 depth/1311868190.433995.png
1311868190.468862 rgb/1311868190.468862.png 1311868190.466043 depth/1311868190.466043.png
1311868190.503067 rgb/1311868190.503067.png 1311868190.503079 depth/1311868190.503079.png
1311868190.536577 rgb/1311868190.536577.png 1311868190.535552 depth/1311868190.535552.png
1311868190.568647 rgb/1311868190.568647.png 1311868190.567335 depth/1311868190.567335.png
1311868190.604416 rgb/1311868190.604416.png 1311868190.604442 depth/1311868190.604442.png
1311868190.636584 rgb/1311868190.636584.png 1311868190.634777 depth/1311868190.634777.png
1311868190.668720 rgb/1311868190.668720.png 1311868190.665967 depth/1311868190.665967.png
1311868190.708899 rgb/1311868190.708899.png 1311868190.706805 depth/1311868190.706805.png
1311868190.736730 rgb/1311868190.736730.png 1311868190.735686 depth/1311868190.735686.png
1311868190.771375 rgb/1311868190.771375.png 1311868190.771383 depth/1311868190.771383.png
1311868190.802394 rgb/1311868190.802394.png 1311868190.802404 depth/1311868190.802404.png
1311868190.836629 rgb/1311868190.836629.png 1311868190.834340 depth/1311868190.834340.png
1311868190.870368 rgb/1311868190.870368.png 1311868190.870372 depth/1311868190.870372.png
1311868190.902257 rgb/1311868190.902257.png 1311868190.902535 depth/1311868190.902535.png
1311868190.936594 rgb/1311868190.936594.png 1311868190.934315 depth/1311868190.934315.png
1311868190.970309 rgb/1311868190.970309.png 1311868190.970320 depth/1311868190.970320.png
1311868191.004252 rgb/1311868191.004252.png 1311868191.004259 depth/1311868191.004259.png
1311868191.036646 rgb/1311868191.036646.png 1311868191.034135 depth/1311868191.034135.png
1311868191.074967 rgb/1311868191.074967.png 1311868191.074973 depth/1311868191.074973.png
1311868191.102905 rgb/1311868191.102905.png 1311868191.102919 depth/1311868191.102919.png
1311868191.136667 rgb/1311868191.136667.png 1311868191.134645 depth/1311868191.134645.png
1311868191.170379 rgb/1311868191.170379.png 1311868191.170391 depth/1311868191.170391.png
1311868191.204730 rgb/1311868191.204730.png 1311868191.204203 depth/1311868191.204203.png
1311868191.236855 rgb/1311868191.236855.png 1311868191.234459 depth/1311868191.234459.png
1311868191.270521 rgb/1311868191.270521.png 1311868191.270582 depth/1311868191.270582.png
1311868191.305138 rgb/1311868191.305138.png 1311868191.305161 depth/1311868191.305161.png
1311868191.336788 rgb/1311868191.336788.png 1311868191.335917 depth/1311868191.335917.png
1311868191.370175 rgb/1311868191.370175.png 1311868191.370183 depth/1311868191.370183.png
1311868191.408020 rgb/1311868191.408020.png 1311868191.404166 depth/1311868191.404166.png
1311868191.436687 rgb/1311868191.436687.png 1311868191.434025 depth/1311868191.434025.png
1311868191.470045 rgb/1311868191.470045.png 1311868191.470054 depth/1311868191.470054.png
1311868191.505579 rgb/1311868191.505579.png 1311868191.503245 depth/1311868191.503245.png
1311868191.536752 rgb/1311868191.536752.png 1311868191.534020 depth/1311868191.534020.png
1311868191.570203 rgb/1311868191.570203.png 1311868191.570221 depth/1311868191.570221.png
1311868191.604658 rgb/1311868191.604658.png 1311868191.602059 depth/1311868191.602059.png
1311868191.636913 rgb/1311868191.636913.png 1311868191.635708 depth/1311868191.635708.png
1311868191.670782 rgb/1311868191.670782.png 1311868191.670789 depth/1311868191.670789.png
1311868191.705077 rgb/1311868191.705077.png 1311868191.701998 depth/1311868191.701998.png
1311868191.736754 rgb/1311868191.736754.png 1311868191.734633 depth/1311868191.734633.png
1311868191.771559 rgb/1311868191.771559.png 1311868191.771577 depth/1311868191.771577.png
1311868191.804765 rgb/1311868191.804765.png 1311868191.802566 depth/1311868191.802566.png
1311868191.836740 rgb/1311868191.836740.png 1311868191.834152 depth/1311868191.834152.png
1311868191.872176 rgb/1311868191.872176.png 1311868191.872199 depth/1311868191.872199.png
1311868191.904702 rgb/1311868191.904702.png 1311868191.902089 depth/1311868191.902089.png
1311868191.936673 rgb/1311868191.936673.png 1311868191.934645 depth/1311868191.934645.png
1311868191.970293 rgb/1311868191.970293.png 1311868191.970309 depth/1311868191.970309.png
1311868192.005218 rgb/1311868192.005218.png 1311868192.002518 depth/1311868192.002518.png
1311868192.038266 rgb/1311868192.038266.png 1311868192.038276 depth/1311868192.038276.png
1311868192.070578 rgb/1311868192.070578.png 1311868192.070588 depth/1311868192.070588.png
1311868192.105561 rgb/1311868192.105561.png 1311868192.102192 depth/1311868192.102192.png
1311868192.139401 rgb/1311868192.139401.png 1311868192.139413 depth/1311868192.139413.png
1311868192.173682 rgb/1311868192.173682.png 1311868192.173696 depth/1311868192.173696.png
1311868192.204710 rgb/1311868192.204710.png 1311868192.203139 depth/1311868192.203139.png
1311868192.240525 rgb/1311868192.240525.png 1311868192.240535 depth/1311868192.240535.png
1311868192.271675 rgb/1311868192.271675.png 1311868192.271684 depth/1311868192.271684.png
1311868192.304674 rgb/1311868192.304674.png 1311868192.302347 depth/1311868192.302347.png
1311868192.342496 rgb/1311868192.342496.png 1311868192.342506 depth/1311868192.342506.png
1311868192.370163 rgb/1311868192.370163.png 1311868192.370177 depth/1311868192.370177.png
1311868192.404725 rgb/1311868192.404725.png 1311868192.402524 depth/1311868192.402524.png
1311868192.438459 rgb/1311868192.438459.png 1311868192.438489 depth/1311868192.438489.png
1311868192.471387 rgb/1311868192.471387.png 1311868192.471399 depth/1311868192.471399.png
1311868192.504708 rgb/1311868192.504708.png 1311868192.502226 depth/1311868192.502226.png
1311868192.540878 rgb/1311868192.540878.png 1311868192.540885 depth/1311868192.540885.png
1311868192.571208 rgb/1311868192.571208.png 1311868192.571226 depth/1311868192.571226.png
1311868192.604784 rgb/1311868192.604784.png 1311868192.603057 depth/1311868192.603057.png
1311868192.641130 rgb/1311868192.641130.png 1311868192.640802 depth/1311868192.640802.png
1311868192.670331 rgb/1311868192.670331.png 1311868192.670341 depth/1311868192.670341.png
1311868192.704764 rgb/1311868192.704764.png 1311868192.702955 depth/1311868192.702955.png
1311868192.739392 rgb/1311868192.739392.png 1311868192.739404 depth/1311868192.739404.png
1311868192.770014 rgb/1311868192.770014.png 1311868192.770022 depth/1311868192.770022.png
1311868192.804785 rgb/1311868192.804785.png 1311868192.802140 depth/1311868192.802140.png
1311868192.838042 rgb/1311868192.838042.png 1311868192.838070 depth/1311868192.838070.png
1311868192.870604 rgb/1311868192.870604.png 1311868192.870622 depth/1311868192.870622.png
1311868192.904715 rgb/1311868192.904715.png 1311868192.902442 depth/1311868192.902442.png
1311868192.940507 rgb/1311868192.940507.png 1311868192.940521 depth/1311868192.940521.png
1311868192.970299 rgb/1311868192.970299.png 1311868192.970546 depth/1311868192.970546.png
1311868193.004778 rgb/1311868193.004778.png 1311868193.004227 depth/1311868193.004227.png
1311868193.038080 rgb/1311868193.038080.png 1311868193.038088 depth/1311868193.038088.png
1311868193.070262 rgb/1311868193.070262.png 1311868193.070274 depth/1311868193.070274.png
1311868193.105256 rgb/1311868193.105256.png 1311868193.104514 depth/1311868193.104514.png
1311868193.140696 rgb/1311868193.140696.png 1311868193.140748 depth/1311868193.140748.png
1311868193.172573 rgb/1311868193.172573.png 1311868193.172593 depth/1311868193.172593.png
1311868193.205121 rgb/1311868193.205121.png 1311868193.203431 depth/1311868193.203431.png
1311868193.238476 rgb/1311868193.238476.png 1311868193.238522 depth/1311868193.238522.png
1311868193.270506 rgb/1311868193.270506.png 1311868193.270532 depth/1311868193.270532.png
1311868193.309034 rgb/1311868193.309034.png 1311868193.309045 depth/1311868193.309045.png
1311868193.340807 rgb/1311868193.340807.png 1311868193.340814 depth/1311868193.340814.png
1311868193.370907 rgb/1311868193.370907.png 1311868193.370916 depth/1311868193.370916.png
1311868193.409261 rgb/1311868193.409261.png 1311868193.409280 depth/1311868193.409280.png
1311868193.438985 rgb/1311868193.438985.png 1311868193.438729 depth/1311868193.438729.png
1311868193.473196 rgb/1311868193.473196.png 1311868193.473222 depth/1311868193.473222.png
1311868193.507782 rgb/1311868193.507782.png 1311868193.508086 depth/1311868193.508086.png
1311868193.541208 rgb/1311868193.541208.png 1311868193.541226 depth/1311868193.541226.png
1311868193.573764 rgb/1311868193.573764.png 1311868193.573781 depth/1311868193.573781.png
1311868193.605992 rgb/1311868193.605992.png 1311868193.606002 depth/1311868193.606002.png
1311868193.640297 rgb/1311868193.640297.png 1311868193.640306 depth/1311868193.640306.png
1311868193.670172 rgb/1311868193.670172.png 1311868193.670184 depth/1311868193.670184.png
1311868193.710143 rgb/1311868193.710143.png 1311868193.710151 depth/1311868193.710151.png
1311868193.738312 rgb/1311868193.738312.png 1311868193.738320 depth/1311868193.738320.png
1311868193.771597 rgb/1311868193.771597.png 1311868193.771612 depth/1311868193.771612.png
1311868193.809392 rgb/1311868193.809392.png 1311868193.809409 depth/1311868193.809409.png
1311868193.838095 rgb/1311868193.838095.png 1311868193.838099 depth/1311868193.838099.png
1311868193.873184 rgb/1311868193.873184.png 1311868193.873191 depth/1311868193.873191.png
1311868193.909419 rgb/1311868193.909419.png 1311868193.909428 depth/1311868193.909428.png
1311868193.938105 rgb/1311868193.938105.png 1311868193.938115 depth/1311868193.938115.png
1311868193.972816 rgb/1311868193.972816.png 1311868193.972826 depth/1311868193.972826.png
1311868194.009150 rgb/1311868194.009150.png 1311868194.009159 depth/1311868194.009159.png
1311868194.038215 rgb/1311868194.038215.png 1311868194.038257 depth/1311868194.038257.png
1311868194.071381 rgb/1311868194.071381.png 1311868194.071393 depth/1311868194.071393.png
1311868194.108743 rgb/1311868194.108743.png 1311868194.108767 depth/1311868194.108767.png
1311868194.140638 rgb/1311868194.140638.png 1311868194.140647 depth/1311868194.140647.png
1311868194.172673 rgb/1311868194.172673.png 1311868194.172696 depth/1311868194.172696.png
1311868194.209517 rgb/1311868194.209517.png 1311868194.209560 depth/1311868194.209560.png
1311868194.243018 rgb/1311868194.243018.png 1311868194.243103 depth/1311868194.243103.png
1311868194.270035 rgb/1311868194.270035.png 1311868194.270044 depth/1311868194.270044.png
1311868194.309378 rgb/1311868194.309378.png 1311868194.309425 depth/1311868194.309425.png
1311868194.339184 rgb/1311868194.339184.png 1311868194.339216 depth/1311868194.339216.png
1311868194.370242 rgb/1311868194.370242.png 1311868194.370251 depth/1311868194.370251.png
1311868194.408223 rgb/1311868194.408223.png 1311868194.408235 depth/1311868194.408235.png
1311868194.439940 rgb/1311868194.439940.png 1311868194.439954 depth/1311868194.439954.png
1311868194.468912 rgb/1311868194.468912.png 1311868194.479894 depth/1311868194.479894.png
1311868194.508854 rgb/1311868194.508854.png 1311868194.508914 depth/1311868194.508914.png
1311868194.538360 rgb/1311868194.538360.png 1311868194.538378 depth/1311868194.538378.png
1311868194.568867 rgb/1311868194.568867.png 1311868194.575743 depth/1311868194.575743.png
1311868194.609529 rgb/1311868194.609529.png 1311868194.609573 depth/1311868194.609573.png
1311868194.645036 rgb/1311868194.645036.png 1311868194.644750 depth/1311868194.644750.png
1311868194.669010 rgb/1311868194.669010.png 1311868194.675892 depth/1311868194.675892.png
1311868194.710055 rgb/1311868194.710055.png 1311868194.710102 depth/1311868194.710102.png
1311868194.740970 rgb/1311868194.740970.png 1311868194.740981 depth/1311868194.740981.png
1311868194.768994 rgb/1311868194.768994.png 1311868194.775988 depth/1311868194.775988.png
1311868194.806949 rgb/1311868194.806949.png 1311868194.806957 depth/1311868194.806957.png
1311868194.842311 rgb/1311868194.842311.png 1311868194.842323 depth/1311868194.842323.png
1311868194.868966 rgb/1311868194.868966.png 1311868194.876176 depth/1311868194.876176.png
1311868194.909237 rgb/1311868194.909237.png 1311868194.909258 depth/1311868194.909258.png
1311868194.942724 rgb/1311868194.942724.png 1311868194.942743 depth/1311868194.942743.png
1311868194.968884 rgb/1311868194.968884.png 1311868194.974494 depth/1311868194.974494.png
1311868195.009219 rgb/1311868195.009219.png 1311868195.009261 depth/1311868195.009261.png
1311868195.038705 rgb/1311868195.038705.png 1311868195.038716 depth/1311868195.038716.png
1311868195.068954 rgb/1311868195.068954.png 1311868195.080005 depth/1311868195.080005.png
1311868195.109504 rgb/1311868195.109504.png 1311868195.109514 depth/1311868195.109514.png
1311868195.139745 rgb/1311868195.139745.png 1311868195.139752 depth/1311868195.139752.png
1311868195.168943 rgb/1311868195.168943.png 1311868195.174446 depth/1311868195.174446.png
1311868195.208719 rgb/1311868195.208719.png 1311868195.208730 depth/1311868195.208730.png
1311868195.238370 rgb/1311868195.238370.png 1311868195.238377 depth/1311868195.238377.png
1311868195.269090 rgb/1311868195.269090.png 1311868195.277414 depth/1311868195.277414.png
1311868195.314009 rgb/1311868195.314009.png 1311868195.309563 depth/1311868195.309563.png
1311868195.340715 rgb/1311868195.340715.png 1311868195.340732 depth/1311868195.340732.png
1311868195.368984 rgb/1311868195.368984.png 1311868195.375835 depth/1311868195.375835.png
1311868195.409401 rgb/1311868195.409401.png 1311868195.409446 depth/1311868195.409446.png
1311868195.441781 rgb/1311868195.441781.png 1311868195.441795 depth/1311868195.441795.png
1311868195.469182 rgb/1311868195.469182.png 1311868195.475479 depth/1311868195.475479.png
1311868195.508972 rgb/1311868195.508972.png 1311868195.509060 depth/1311868195.509060.png
1311868195.540776 rgb/1311868195.540776.png 1311868195.540792 depth/1311868195.540792.png
1311868195.569178 rgb/1311868195.569178.png 1311868195.576256 depth/1311868195.576256.png
1311868195.607032 rgb/1311868195.607032.png 1311868195.607072 depth/1311868195.607072.png
1311868195.641375 rgb/1311868195.641375.png 1311868195.641383 depth/1311868195.641383.png
1311868195.669012 rgb/1311868195.669012.png 1311868195.674270 depth/1311868195.674270.png
1311868195.710126 rgb/1311868195.710126.png 1311868195.710169 depth/1311868195.710169.png
1311868195.737290 rgb/1311868195.737290.png 1311868195.742482 depth/1311868195.742482.png
1311868195.769034 rgb/1311868195.769034.png 1311868195.778577 depth/1311868195.778577.png
1311868195.808835 rgb/1311868195.808835.png 1311868195.808879 depth/1311868195.808879.png
1311868195.837123 rgb/1311868195.837123.png 1311868195.842970 depth/1311868195.842970.png
1311868195.869116 rgb/1311868195.869116.png 1311868195.874786 depth/1311868195.874786.png
1311868195.906456 rgb/1311868195.906456.png 1311868195.906472 depth/1311868195.906472.png
1311868195.936986 rgb/1311868195.936986.png 1311868195.948982 depth/1311868195.948982.png
1311868195.969019 rgb/1311868195.969019.png 1311868195.976672 depth/1311868195.976672.png
1311868196.009280 rgb/1311868196.009280.png 1311868196.009295 depth/1311868196.009295.png
1311868196.036924 rgb/1311868196.036924.png 1311868196.049302 depth/1311868196.049302.png
1311868196.068988 rgb/1311868196.068988.png 1311868196.083048 depth/1311868196.083048.png
1311868196.107842 rgb/1311868196.107842.png 1311868196.107854 depth/1311868196.107854.png
1311868196.137076 rgb/1311868196.137076.png 1311868196.147737 depth/1311868196.147737.png
1311868196.168888 rgb/1311868196.168888.png 1311868196.174813 depth/1311868196.174813.png
1311868196.208314 rgb/1311868196.208314.png 1311868196.208324 depth/1311868196.208324.png
1311868196.236975 rgb/1311868196.236975.png 1311868196.244116 depth/1311868196.244116.png
1311868196.269144 rgb/1311868196.269144.png 1311868196.279999 depth/1311868196.279999.png
1311868196.307425 rgb/1311868196.307425.png 1311868196.307458 depth/1311868196.307458.png
1311868196.337126 rgb/1311868196.337126.png 1311868196.344161 depth/1311868196.344161.png
1311868196.369056 rgb/1311868196.369056.png 1311868196.380429 depth/1311868196.380429.png
1311868196.410126 rgb/1311868196.410126.png 1311868196.410168 depth/1311868196.410168.png
1311868196.437163 rgb/1311868196.437163.png 1311868196.446202 depth/1311868196.446202.png
1311868196.468966 rgb/1311868196.468966.png 1311868196.479745 depth/1311868196.479745.png
1311868196.507765 rgb/1311868196.507765.png 1311868196.507227 depth/1311868196.507227.png
1311868196.537088 rgb/1311868196.537088.png 1311868196.542843 depth/1311868196.542843.png
1311868196.569054 rgb/1311868196.569054.png 1311868196.578865 depth/1311868196.578865.png
1311868196.610073 rgb/1311868196.610073.png 1311868196.610088 depth/1311868196.610088.png
1311868196.637007 rgb/1311868196.637007.png 1311868196.648433 depth/1311868196.648433.png
1311868196.668957 rgb/1311868196.668957.png 1311868196.674864 depth/1311868196.674864.png
1311868196.709665 rgb/1311868196.709665.png 1311868196.709712 depth/1311868196.709712.png
1311868196.737079 rgb/1311868196.737079.png 1311868196.743666 depth/1311868196.743666.png
1311868196.769084 rgb/1311868196.769084.png 1311868196.780049 depth/1311868196.780049.png
1311868196.807613 rgb/1311868196.807613.png 1311868196.807621 depth/1311868196.807621.png
1311868196.837005 rgb/1311868196.837005.png 1311868196.844319 depth/1311868196.844319.png
1311868196.869030 rgb/1311868196.869030.png 1311868196.876970 depth/1311868196.876970.png
1311868196.909608 rgb/1311868196.909608.png 1311868196.909614 depth/1311868196.909614.png
1311868196.936988 rgb/1311868196.936988.png 1311868196.947288 depth/1311868196.947288.png
1311868196.969198 rgb/1311868196.969198.png 1311868196.978330 depth/1311868196.978330.png
1311868197.005107 rgb/1311868197.005107.png 1311868197.014534 depth/1311868197.014534.png
1311868197.036991 rgb/1311868197.036991.png 1311868197.046602 depth/1311868197.046602.png
1311868197.069116 rgb/1311868197.069116.png 1311868197.077214 depth/1311868197.077214.png
1311868197.105017 rgb/1311868197.105017.png 1311868197.115217 depth/1311868197.115217.png
1311868197.136991 rgb/1311868197.136991.png 1311868197.148846 depth/1311868197.148846.png
1311868197.169013 rgb/1311868197.169013.png 1311868197.176697 depth/1311868197.176697.png
1311868197.205086 rgb/1311868197.205086.png 1311868197.215804 depth/1311868197.215804.png
1311868197.237163 rgb/1311868197.237163.png 1311868197.244642 depth/1311868197.244642.png
1311868197.269183 rgb/1311868197.269183.png 1311868197.278421 depth/1311868197.278421.png
1311868197.305116 rgb/1311868197.305116.png 1311868197.316544 depth/1311868197.316544.png
1311868197.337258 rgb/1311868197.337258.png 1311868197.350515 depth/1311868197.350515.png
1311868197.369073 rgb/1311868197.369073.png 1311868197.374671 depth/1311868197.374671.png
1311868197.405204 rgb/1311868197.405204.png 1311868197.413967 depth/1311868197.413967.png
1311868197.437047 rgb/1311868197.437047.png 1311868197.443603 depth/1311868197.443603.png
1311868197.469173 rgb/1311868197.469173.png 1311868197.478009 depth/1311868197.478009.png
1311868197.505155 rgb/1311868197.505155.png 1311868197.514831 depth/1311868197.514831.png
1311868197.536977 rgb/1311868197.536977.png 1311868197.545046 depth/1311868197.545046.png
1311868197.569185 rgb/1311868197.569185.png 1311868197.578115 depth/1311868197.578115.png
1311868197.605169 rgb/1311868197.605169.png 1311868197.614158 depth/1311868197.614158.png
1311868197.637079 rgb/1311868197.637079.png 1311868197.648960 depth/1311868197.648960.png
1311868197.669130 rgb/1311868197.669130.png 1311868197.677623 depth/1311868197.677623.png
1311868197.705186 rgb/1311868197.705186.png 1311868197.713383 depth/1311868197.713383.png
1311868197.737277 rgb/1311868197.737277.png 1311868197.749245 depth/1311868197.749245.png
1311868197.769193 rgb/1311868197.769193.png 1311868197.777176 depth/1311868197.777176.png
1311868197.805395 rgb/1311868197.805395.png 1311868197.814720 depth/1311868197.814720.png
1311868197.837217 rgb/1311868197.837217.png 1311868197.846941 depth/1311868197.846941.png
1311868197.869114 rgb/1311868197.869114.png 1311868197.877369 depth/1311868197.877369.png
1311868197.905203 rgb/1311868197.905203.png 1311868197.915506 depth/1311868197.915506.png
1311868197.937196 rgb/1311868197.937196.png 1311868197.947225 depth/1311868197.947225.png
1311868197.969193 rgb/1311868197.969193.png 1311868197.976646 depth/1311868197.976646.png
1311868198.005244 rgb/1311868198.005244.png 1311868198.015692 depth/1311868198.015692.png
1311868198.037139 rgb/1311868198.037139.png 1311868198.047426 depth/1311868198.047426.png
1311868198.069220 rgb/1311868198.069220.png 1311868198.077753 depth/1311868198.077753.png
1311868198.105370 rgb/1311868198.105370.png 1311868198.115270 depth/1311868198.115270.png
1311868198.137212 rgb/1311868198.137212.png 1311868198.149620 depth/1311868198.149620.png
1311868198.169159 rgb/1311868198.169159.png 1311868198.180637 depth/1311868198.180637.png
1311868198.205266 rgb/1311868198.205266.png 1311868198.217618 depth/1311868198.217618.png
1311868198.237167 rgb/1311868198.237167.png 1311868198.248693 depth/1311868198.248693.png
1311868198.269205 rgb/1311868198.269205.png 1311868198.283148 depth/1311868198.283148.png
1311868198.305141 rgb/1311868198.305141.png 1311868198.314134 depth/1311868198.314134.png
1311868198.337248 rgb/1311868198.337248.png 1311868198.345640 depth/1311868198.345640.png
1311868198.369167 rgb/1311868198.369167.png 1311868198.385094 depth/1311868198.385094.png
1311868198.405114 rgb/1311868198.405114.png 1311868198.413332 depth/1311868198.413332.png
1311868198.437155 rgb/1311868198.437155.png 1311868198.444494 depth/1311868198.444494.png
1311868198.469161 rgb/1311868198.469161.png 1311868198.482279 depth/1311868198.482279.png
1311868198.505259 rgb/1311868198.505259.png 1311868198.514834 depth/1311868198.514834.png
1311868198.537261 rgb/1311868198.537261.png 1311868198.545660 depth/1311868198.545660.png
1311868198.569178 rgb/1311868198.569178.png 1311868198.582335 depth/1311868198.582335.png
1311868198.605102 rgb/1311868198.605102.png 1311868198.613448 depth/1311868198.613448.png
1311868198.637155 rgb/1311868198.637155.png 1311868198.643839 depth/1311868198.643839.png
1311868198.669124 rgb/1311868198.669124.png 1311868198.680098 depth/1311868198.680098.png
1311868198.705029 rgb/1311868198.705029.png 1311868198.714601 depth/1311868198.714601.png
1311868198.737178 rgb/1311868198.737178.png 1311868198.744612 depth/1311868198.744612.png
1311868198.769148 rgb/1311868198.769148.png 1311868198.781251 depth/1311868198.781251.png
1311868198.805122 rgb/1311868198.805122.png 1311868198.812579 depth/1311868198.812579.png
1311868198.837189 rgb/1311868198.837189.png 1311868198.846157 depth/1311868198.846157.png
1311868198.869154 rgb/1311868198.869154.png 1311868198.882317 depth/1311868198.882317.png
1311868198.905110 rgb/1311868198.905110.png 1311868198.911755 depth/1311868198.911755.png
1311868198.937129 rgb/1311868198.937129.png 1311868198.944555 depth/1311868198.944555.png
1311868198.969249 rgb/1311868198.969249.png 1311868198.983467 depth/1311868198.983467.png
1311868199.005125 rgb/1311868199.005125.png 1311868199.013481 depth/1311868199.013481.png
1311868199.037153 rgb/1311868199.037153.png 1311868199.043568 depth/1311868199.043568.png
1311868199.069162 rgb/1311868199.069162.png 1311868199.080481 depth/1311868199.080481.png
1311868199.105139 rgb/1311868199.105139.png 1311868199.112174 depth/1311868199.112174.png
1311868199.137202 rgb/1311868199.137202.png 1311868199.143350 depth/1311868199.143350.png
1311868199.169310 rgb/1311868199.169310.png 1311868199.180369 depth/1311868199.180369.png
1311868199.205167 rgb/1311868199.205167.png 1311868199.211722 depth/1311868199.211722.png
1311868199.237228 rgb/1311868199.237228.png 1311868199.245452 depth/1311868199.245452.png
1311868199.269349 rgb/1311868199.269349.png 1311868199.280416 depth/1311868199.280416.png
1311868199.305204 rgb/1311868199.305204.png 1311868199.311451 depth/1311868199.311451.png
1311868199.337251 rgb/1311868199.337251.png 1311868199.343792 depth/1311868199.343792.png
1311868199.369357 rgb/1311868199.369357.png 1311868199.381815 depth/1311868199.381815.png
1311868199.405159 rgb/1311868199.405159.png 1311868199.413160 depth/1311868199.413160.png
1311868199.437214 rgb/1311868199.437214.png 1311868199.449365 depth/1311868199.449365.png
1311868199.469396 rgb/1311868199.469396.png 1311868199.481210 depth/1311868199.481210.png
1311868199.505308 rgb/1311868199.505308.png 1311868199.512945 depth/1311868199.512945.png
1311868199.537263 rgb/1311868199.537263.png 1311868199.548273 depth/1311868199.548273.png
1311868199.569325 rgb/1311868199.569325.png 1311868199.580844 depth/1311868199.580844.png
1311868199.605264 rgb/1311868199.605264.png 1311868199.613118 depth/1311868199.613118.png
1311868199.637203 rgb/1311868199.637203.png 1311868199.647673 depth/1311868199.647673.png
1311868199.669160 rgb/1311868199.669160.png 1311868199.681036 depth/1311868199.681036.png
1311868199.705305 rgb/1311868199.705305.png 1311868199.713851 depth/1311868199.713851.png
1311868199.737153 rgb/1311868199.737153.png 1311868199.748271 depth/1311868199.748271.png
1311868199.769136 rgb/1311868199.769136.png 1311868199.781068 depth/1311868199.781068.png
1311868199.805309 rgb/1311868199.805309.png 1311868199.813002 depth/1311868199.813002.png
1311868199.837168 rgb/1311868199.837168.png 1311868199.849238 depth/1311868199.849238.png
1311868199.869232 rgb/1311868199.869232.png 1311868199.881699 depth/1311868199.881699.png
1311868199.905169 rgb/1311868199.905169.png 1311868199.915637 depth/1311868199.915637.png
1311868199.937209 rgb/1311868199.937209.png 1311868199.949425 depth/1311868199.949425.png
1311868199.969272 rgb/1311868199.969272.png 1311868199.981328 depth/1311868199.981328.png
1311868200.005247 rgb/1311868200.005247.png 1311868200.011907 depth/1311868200.011907.png
1311868200.037557 rgb/1311868200.037557.png 1311868200.048486 depth/1311868200.048486.png
1311868200.069418 rgb/1311868200.069418.png 1311868200.080921 depth/1311868200.080921.png
1311868200.105179 rgb/1311868200.105179.png 1311868200.111308 depth/1311868200.111308.png
1311868200.137281 rgb/1311868200.137281.png 1311868200.149780 depth/1311868200.149780.png
1311868200.169388 rgb/1311868200.169388.png 1311868200.182269 depth/1311868200.182269.png
1311868200.205451 rgb/1311868200.205451.png 1311868200.212926 depth/1311868200.212926.png
1311868200.237169 rgb/1311868200.237169.png 1311868200.247733 depth/1311868200.247733.png
1311868200.273397 rgb/1311868200.273397.png 1311868200.280294 depth/1311868200.280294.png
1311868200.305197 rgb/1311868200.305197.png 1311868200.315750 depth/1311868200.315750.png
1311868200.337233 rgb/1311868200.337233.png 1311868200.348252 depth/1311868200.348252.png
1311868200.373427 rgb/1311868200.373427.png 1311868200.380528 depth/1311868200.380528.png
1311868200.405205 rgb/1311868200.405205.png 1311868200.412060 depth/1311868200.412060.png
1311868200.437327 rgb/1311868200.437327.png 1311868200.449108 depth/1311868200.449108.png
1311868200.473305 rgb/1311868200.473305.png 1311868200.485010 depth/1311868200.485010.png
1311868200.505347 rgb/1311868200.505347.png 1311868200.515841 depth/1311868200.515841.png
1311868200.537240 rgb/1311868200.537240.png 1311868200.548967 depth/1311868200.548967.png
1311868200.573293 rgb/1311868200.573293.png 1311868200.582157 depth/1311868200.582157.png
1311868200.605204 rgb/1311868200.605204.png 1311868200.613020 depth/1311868200.613020.png
1311868200.637423 rgb/1311868200.637423.png 1311868200.648629 depth/1311868200.648629.png
1311868200.673455 rgb/1311868200.673455.png 1311868200.679698 depth/1311868200.679698.png
1311868200.705281 rgb/1311868200.705281.png 1311868200.717862 depth/1311868200.717862.png
1311868200.737553 rgb/1311868200.737553.png 1311868200.748941 depth/1311868200.748941.png
1311868200.773365 rgb/1311868200.773365.png 1311868200.779204 depth/1311868200.779204.png
1311868200.805217 rgb/1311868200.805217.png 1311868200.817259 depth/1311868200.817259.png
1311868200.837445 rgb/1311868200.837445.png 1311868200.848927 depth/1311868200.848927.png
1311868200.873224 rgb/1311868200.873224.png 1311868200.881990 depth/1311868200.881990.png
1311868200.905248 rgb/1311868200.905248.png 1311868200.916807 depth/1311868200.916807.png
1311868200.937356 rgb/1311868200.937356.png 1311868200.948795 depth/1311868200.948795.png
1311868200.973447 rgb/1311868200.973447.png 1311868200.981350 depth/1311868200.981350.png
1311868201.005304 rgb/1311868201.005304.png 1311868201.016041 depth/1311868201.016041.png
1311868201.037420 rgb/1311868201.037420.png 1311868201.048622 depth/1311868201.048622.png
1311868201.073245 rgb/1311868201.073245.png 1311868201.081466 depth/1311868201.081466.png
1311868201.105420 rgb/1311868201.105420.png 1311868201.117905 depth/1311868201.117905.png
1311868201.137460 rgb/1311868201.137460.png 1311868201.147308 depth/1311868201.147308.png
1311868201.173508 rgb/1311868201.173508.png 1311868201.182445 depth/1311868201.182445.png
1311868201.205336 rgb/1311868201.205336.png 1311868201.216734 depth/1311868201.216734.png
1311868201.237377 rgb/1311868201.237377.png 1311868201.247293 depth/1311868201.247293.png
1311868201.273379 rgb/1311868201.273379.png 1311868201.284041 depth/1311868201.284041.png
1311868201.305293 rgb/1311868201.305293.png 1311868201.318421 depth/1311868201.318421.png
1311868201.337491 rgb/1311868201.337491.png 1311868201.349439 depth/1311868201.349439.png
1311868201.373318 rgb/1311868201.373318.png 1311868201.383094 depth/1311868201.383094.png
1311868201.405299 rgb/1311868201.405299.png 1311868201.415370 depth/1311868201.415370.png
1311868201.437414 rgb/1311868201.437414.png 1311868201.447869 depth/1311868201.447869.png
1311868201.473238 rgb/1311868201.473238.png 1311868201.480785 depth/1311868201.480785.png
1311868201.505318 rgb/1311868201.505318.png 1311868201.518411 depth/1311868201.518411.png
1311868201.537450 rgb/1311868201.537450.png 1311868201.548346 depth/1311868201.548346.png
1311868201.573409 rgb/1311868201.573409.png 1311868201.584133 depth/1311868201.584133.png
1311868201.605366 rgb/1311868201.605366.png 1311868201.618693 depth/1311868201.618693.png
1311868201.637398 rgb/1311868201.637398.png 1311868201.648110 depth/1311868201.648110.png
1311868201.673519 rgb/1311868201.673519.png 1311868201.682146 depth/1311868201.682146.png
1311868201.705356 rgb/1311868201.705356.png 1311868201.717094 depth/1311868201.717094.png
1311868201.737412 rgb/1311868201.737412.png 1311868201.750216 depth/1311868201.750216.png
1311868201.773466 rgb/1311868201.773466.png 1311868201.782412 depth/1311868201.782412.png
1311868201.805263 rgb/1311868201.805263.png 1311868201.816684 depth/1311868201.816684.png
1311868201.837447 rgb/1311868201.837447.png 1311868201.849496 depth/1311868201.849496.png
1311868201.873269 rgb/1311868201.873269.png 1311868201.886245 depth/1311868201.886245.png
1311868201.905252 rgb/1311868201.905252.png 1311868201.915736 depth/1311868201.915736.png
1311868201.937456 rgb/1311868201.937456.png 1311868201.948414 depth/1311868201.948414.png
1311868201.973324 rgb/1311868201.973324.png 1311868201.988190 depth/1311868201.988190.png
1311868202.005324 rgb/1311868202.005324.png 1311868202.020311 depth/1311868202.020311.png
1311868202.037477 rgb/1311868202.037477.png 1311868202.050750 depth/1311868202.050750.png
1311868202.073300 rgb/1311868202.073300.png 1311868202.084295 depth/1311868202.084295.png
1311868202.105342 rgb/1311868202.105342.png 1311868202.116660 depth/1311868202.116660.png
1311868202.137626 rgb/1311868202.137626.png 1311868202.148960 depth/1311868202.148960.png
1311868202.173321 rgb/1311868202.173321.png 1311868202.185316 depth/1311868202.185316.png
1311868202.205344 rgb/1311868202.205344.png 1311868202.220704 depth/1311868202.220704.png
1311868202.237472 rgb/1311868202.237472.png 1311868202.248221 depth/1311868202.248221.png
1311868202.273322 rgb/1311868202.273322.png 1311868202.284706 depth/1311868202.284706.png
1311868202.305308 rgb/1311868202.305308.png 1311868202.315907 depth/1311868202.315907.png
1311868202.337417 rgb/1311868202.337417.png 1311868202.350180 depth/1311868202.350180.png
1311868202.373252 rgb/1311868202.373252.png 1311868202.385307 depth/1311868202.385307.png
1311868202.405338 rgb/1311868202.405338.png 1311868202.418776 depth/1311868202.418776.png
1311868202.437436 rgb/1311868202.437436.png 1311868202.449207 depth/1311868202.449207.png
1311868202.473421 rgb/1311868202.473421.png 1311868202.486886 depth/1311868202.486886.png
1311868202.505419 rgb/1311868202.505419.png 1311868202.517269 depth/1311868202.517269.png
1311868202.537451 rgb/1311868202.537451.png 1311868202.550209 depth/1311868202.550209.png
1311868202.573395 rgb/1311868202.573395.png 1311868202.584930 depth/1311868202.584930.png
1311868202.605428 rgb/1311868202.605428.png 1311868202.617698 depth/1311868202.617698.png
1311868202.637392 rgb/1311868202.637392.png 1311868202.651291 depth/1311868202.651291.png
1311868202.673740 rgb/1311868202.673740.png 1311868202.684815 depth/1311868202.684815.png
1311868202.705520 rgb/1311868202.705520.png 1311868202.721423 depth/1311868202.721423.png
1311868202.737342 rgb/1311868202.737342.png 1311868202.750587 depth/1311868202.750587.png
1311868202.773447 rgb/1311868202.773447.png 1311868202.789078 depth/1311868202.789078.png
1311868202.805444 rgb/1311868202.805444.png 1311868202.817783 depth/1311868202.817783.png
1311868202.837625 rgb/1311868202.837625.png 1311868202.847821 depth/1311868202.847821.png
1311868202.873426 rgb/1311868202.873426.png 1311868202.887573 depth/1311868202.887573.png
1311868202.905418 rgb/1311868202.905418.png 1311868202.916713 depth/1311868202.916713.png
1311868202.937647 rgb/1311868202.937647.png 1311868202.950442 depth/1311868202.950442.png
1311868202.973443 rgb/1311868202.973443.png 1311868202.986195 depth/1311868202.986195.png
1311868203.005588 rgb/1311868203.005588.png 1311868203.018688 depth/1311868203.018688.png
1311868203.037557 rgb/1311868203.037557.png 1311868203.051092 depth/1311868203.051092.png
1311868203.073357 rgb/1311868203.073357.png 1311868203.088633 depth/1311868203.088633.png
1311868203.105553 rgb/1311868203.105553.png 1311868203.118553 depth/1311868203.118553.png
1311868203.137538 rgb/1311868203.137538.png 1311868203.151428 depth/1311868203.151428.png
1311868203.173538 rgb/1311868203.173538.png 1311868203.186728 depth/1311868203.186728.png
1311868203.205413 rgb/1311868203.205413.png 1311868203.221978 depth/1311868203.221978.png
1311868203.237522 rgb/1311868203.237522.png 1311868203.251418 depth/1311868203.251418.png
1311868203.273471 rgb/1311868203.273471.png 1311868203.290312 depth/1311868203.290312.png
1311868203.305495 rgb/1311868203.305495.png 1311868203.319511 depth/1311868203.319511.png
1311868203.337532 rgb/1311868203.337532.png 1311868203.355366 depth/1311868203.355366.png
1311868203.373566 rgb/1311868203.373566.png 1311868203.388076 depth/1311868203.388076.png
1311868203.405460 rgb/1311868203.405460.png 1311868203.420300 depth/1311868203.420300.png
1311868203.437674 rgb/1311868203.437674.png 1311868203.452684 depth/1311868203.452684.png
1311868203.505522 rgb/1311868203.505522.png 1311868203.489908 depth/1311868203.489908.png
1311868203.537432 rgb/1311868203.537432.png 1311868203.551488 depth/1311868203.551488.png
1311868203.573541 rgb/1311868203.573541.png 1311868203.590000 depth/1311868203.590000.png
1311868203.605369 rgb/1311868203.605369.png 1311868203.620263 depth/1311868203.620263.png
1311868203.673562 rgb/1311868203.673562.png 1311868203.655631 depth/1311868203.655631.png
1311868203.705515 rgb/1311868203.705515.png 1311868203.693736 depth/1311868203.693736.png
1311868203.737597 rgb/1311868203.737597.png 1311868203.753498 depth/1311868203.753498.png
1311868203.773697 rgb/1311868203.773697.png 1311868203.788292 depth/1311868203.788292.png
1311868203.805515 rgb/1311868203.805515.png 1311868203.819823 depth/1311868203.819823.png
1311868203.837454 rgb/1311868203.837454.png 1311868203.854378 depth/1311868203.854378.png
1311868203.905612 rgb/1311868203.905612.png 1311868203.889896 depth/1311868203.889896.png
1311868203.937698 rgb/1311868203.937698.png 1311868203.922682 depth/1311868203.922682.png
1311868203.973618 rgb/1311868203.973618.png 1311868203.989463 depth/1311868203.989463.png
1311868204.005472 rgb/1311868204.005472.png 1311868204.020950 depth/1311868204.020950.png
1311868204.037612 rgb/1311868204.037612.png 1311868204.053488 depth/1311868204.053488.png
1311868204.073619 rgb/1311868204.073619.png 1311868204.089724 depth/1311868204.089724.png
1311868204.105511 rgb/1311868204.105511.png 1311868204.120304 depth/1311868204.120304.png
1311868204.137666 rgb/1311868204.137666.png 1311868204.153783 depth/1311868204.153783.png
1311868204.173662 rgb/1311868204.173662.png 1311868204.189089 depth/1311868204.189089.png
1311868204.205500 rgb/1311868204.205500.png 1311868204.220000 depth/1311868204.220000.png
1311868204.237660 rgb/1311868204.237660.png 1311868204.254490 depth/1311868204.254490.png
1311868204.273553 rgb/1311868204.273553.png 1311868204.289333 depth/1311868204.289333.png
1311868204.305523 rgb/1311868204.305523.png 1311868204.321788 depth/1311868204.321788.png
1311868204.337676 rgb/1311868204.337676.png 1311868204.353107 depth/1311868204.353107.png
1311868204.373570 rgb/1311868204.373570.png 1311868204.390706 depth/1311868204.390706.png
1311868204.405677 rgb/1311868204.405677.png 1311868204.420594 depth/1311868204.420594.png
1311868204.437659 rgb/1311868204.437659.png 1311868204.452861 depth/1311868204.452861.png
1311868204.473547 rgb/1311868204.473547.png 1311868204.488605 depth/1311868204.488605.png
1311868204.537824 rgb/1311868204.537824.png 1311868204.524765 depth/1311868204.524765.png
1311868204.573698 rgb/1311868204.573698.png 1311868204.589865 depth/1311868204.589865.png
1311868204.605660 rgb/1311868204.605660.png 1311868204.620568 depth/1311868204.620568.png
1311868204.637637 rgb/1311868204.637637.png 1311868204.653105 depth/1311868204.653105.png
1311868204.673697 rgb/1311868204.673697.png 1311868204.688212 depth/1311868204.688212.png
1311868204.705514 rgb/1311868204.705514.png 1311868204.720486 depth/1311868204.720486.png
1311868204.737693 rgb/1311868204.737693.png 1311868204.752331 depth/1311868204.752331.png
1311868204.773695 rgb/1311868204.773695.png 1311868204.788985 depth/1311868204.788985.png
1311868204.837551 rgb/1311868204.837551.png 1311868204.824953 depth/1311868204.824953.png
1311868204.873553 rgb/1311868204.873553.png 1311868204.889201 depth/1311868204.889201.png
1311868204.905660 rgb/1311868204.905660.png 1311868204.920352 depth/1311868204.920352.png
1311868204.937718 rgb/1311868204.937718.png 1311868204.953152 depth/1311868204.953152.png
1311868205.006015 rgb/1311868205.006015.png 1311868204.990689 depth/1311868204.990689.png
1311868205.037739 rgb/1311868205.037739.png 1311868205.025845 depth/1311868205.025845.png
1311868205.073567 rgb/1311868205.073567.png 1311868205.086494 depth/1311868205.086494.png
1311868205.137610 rgb/1311868205.137610.png 1311868205.122568 depth/1311868205.122568.png
1311868205.173557 rgb/1311868205.173557.png 1311868205.188535 depth/1311868205.188535.png
1311868205.205555 rgb/1311868205.205555.png 1311868205.219710 depth/1311868205.219710.png
1311868205.237795 rgb/1311868205.237795.png 1311868205.255934 depth/1311868205.255934.png
1311868205.273577 rgb/1311868205.273577.png 1311868205.289185 depth/1311868205.289185.png
1311868205.305573 rgb/1311868205.305573.png 1311868205.319204 depth/1311868205.319204.png
1311868205.337790 rgb/1311868205.337790.png 1311868205.357323 depth/1311868205.357323.png
1311868205.373547 rgb/1311868205.373547.png 1311868205.389230 depth/1311868205.389230.png
1311868205.405669 rgb/1311868205.405669.png 1311868205.422413 depth/1311868205.422413.png
1311868205.437684 rgb/1311868205.437684.png 1311868205.451557 depth/1311868205.451557.png
1311868205.473609 rgb/1311868205.473609.png 1311868205.487562 depth/1311868205.487562.png
1311868205.505684 rgb/1311868205.505684.png 1311868205.519674 depth/1311868205.519674.png
1311868205.537722 rgb/1311868205.537722.png 1311868205.553390 depth/1311868205.553390.png
1311868205.573643 rgb/1311868205.573643.png 1311868205.586644 depth/1311868205.586644.png
1311868205.605542 rgb/1311868205.605542.png 1311868205.619591 depth/1311868205.619591.png
1311868205.637725 rgb/1311868205.637725.png 1311868205.651913 depth/1311868205.651913.png
1311868205.705594 rgb/1311868205.705594.png 1311868205.690498 depth/1311868205.690498.png
1311868205.737847 rgb/1311868205.737847.png 1311868205.723045 depth/1311868205.723045.png
1311868205.773626 rgb/1311868205.773626.png 1311868205.789006 depth/1311868205.789006.png
1311868205.805674 rgb/1311868205.805674.png 1311868205.821518 depth/1311868205.821518.png
1311868205.837631 rgb/1311868205.837631.png 1311868205.852643 depth/1311868205.852643.png
1311868205.905586 rgb/1311868205.905586.png 1311868205.891319 depth/1311868205.891319.png
1311868205.937758 rgb/1311868205.937758.png 1311868205.921292 depth/1311868205.921292.png
1311868205.973702 rgb/1311868205.973702.png 1311868205.990701 depth/1311868205.990701.png
1311868206.005629 rgb/1311868206.005629.png 1311868206.020176 depth/1311868206.020176.png
1311868206.037992 rgb/1311868206.037992.png 1311868206.053115 depth/1311868206.053115.png
1311868206.105664 rgb/1311868206.105664.png 1311868206.091312 depth/1311868206.091312.png
1311868206.137732 rgb/1311868206.137732.png 1311868206.122346 depth/1311868206.122346.png
1311868206.173808 rgb/1311868206.173808.png 1311868206.190035 depth/1311868206.190035.png
1311868206.205696 rgb/1311868206.205696.png 1311868206.221036 depth/1311868206.221036.png
1311868206.237864 rgb/1311868206.237864.png 1311868206.253907 depth/1311868206.253907.png
1311868206.305562 rgb/1311868206.305562.png 1311868206.289938 depth/1311868206.289938.png
1311868206.337745 rgb/1311868206.337745.png 1311868206.352988 depth/1311868206.352988.png
1311868206.405629 rgb/1311868206.405629.png 1311868206.391438 depth/1311868206.391438.png
1311868206.437725 rgb/1311868206.437725.png 1311868206.422380 depth/1311868206.422380.png
1311868206.473742 rgb/1311868206.473742.png 1311868206.490059 depth/1311868206.490059.png
1311868206.505757 rgb/1311868206.505757.png 1311868206.520856 depth/1311868206.520856.png
1311868206.537710 rgb/1311868206.537710.png 1311868206.554417 depth/1311868206.554417.png
1311868206.573663 rgb/1311868206.573663.png 1311868206.589032 depth/1311868206.589032.png
1311868206.637808 rgb/1311868206.637808.png 1311868206.623746 depth/1311868206.623746.png
1311868206.673806 rgb/1311868206.673806.png 1311868206.689806 depth/1311868206.689806.png
1311868206.705664 rgb/1311868206.705664.png 1311868206.720361 depth/1311868206.720361.png
1311868206.737742 rgb/1311868206.737742.png 1311868206.754103 depth/1311868206.754103.png
1311868206.805720 rgb/1311868206.805720.png 1311868206.792145 depth/1311868206.792145.png
1311868206.837709 rgb/1311868206.837709.png 1311868206.823349 depth/1311868206.823349.png
1311868206.873715 rgb/1311868206.873715.png 1311868206.855875 depth/1311868206.855875.png
1311868206.906005 rgb/1311868206.906005.png 1311868206.892627 depth/1311868206.892627.png
1311868206.938074 rgb/1311868206.938074.png 1311868206.924424 depth/1311868206.924424.png
1311868206.973664 rgb/1311868206.973664.png 1311868206.987416 depth/1311868206.987416.png
1311868207.005651 rgb/1311868207.005651.png 1311868207.019787 depth/1311868207.019787.png
1311868207.073774 rgb/1311868207.073774.png 1311868207.057908 depth/1311868207.057908.png
1311868207.105726 rgb/1311868207.105726.png 1311868207.121576 depth/1311868207.121576.png
1311868207.137747 rgb/1311868207.137747.png 1311868207.154851 depth/1311868207.154851.png
1311868207.205787 rgb/1311868207.205787.png 1311868207.191285 depth/1311868207.191285.png
1311868207.237785 rgb/1311868207.237785.png 1311868207.221222 depth/1311868207.221222.png
1311868207.273845 rgb/1311868207.273845.png 1311868207.289968 depth/1311868207.289968.png
1311868207.305734 rgb/1311868207.305734.png 1311868207.320734 depth/1311868207.320734.png
1311868207.337883 rgb/1311868207.337883.png 1311868207.355453 depth/1311868207.355453.png
1311868207.405766 rgb/1311868207.405766.png 1311868207.390393 depth/1311868207.390393.png
1311868207.437999 rgb/1311868207.437999.png 1311868207.424233 depth/1311868207.424233.png
1311868207.473631 rgb/1311868207.473631.png 1311868207.460003 depth/1311868207.460003.png
1311868207.505671 rgb/1311868207.505671.png 1311868207.490256 depth/1311868207.490256.png
1311868207.537787 rgb/1311868207.537787.png 1311868207.522440 depth/1311868207.522440.png
1311868207.573858 rgb/1311868207.573858.png 1311868207.558020 depth/1311868207.558020.png
1311868207.605696 rgb/1311868207.605696.png 1311868207.592021 depth/1311868207.592021.png
1311868207.637684 rgb/1311868207.637684.png 1311868207.620945 depth/1311868207.620945.png
1311868207.673813 rgb/1311868207.673813.png 1311868207.660880 depth/1311868207.660880.png
1311868207.705850 rgb/1311868207.705850.png 1311868207.690675 depth/1311868207.690675.png
1311868207.737830 rgb/1311868207.737830.png 1311868207.723433 depth/1311868207.723433.png
1311868207.773705 rgb/1311868207.773705.png 1311868207.756243 depth/1311868207.756243.png
1311868207.805764 rgb/1311868207.805764.png 1311868207.791829 depth/1311868207.791829.png
1311868207.837900 rgb/1311868207.837900.png 1311868207.819777 depth/1311868207.819777.png
1311868207.873905 rgb/1311868207.873905.png 1311868207.860113 depth/1311868207.860113.png
1311868207.905716 rgb/1311868207.905716.png 1311868207.888571 depth/1311868207.888571.png
1311868207.937792 rgb/1311868207.937792.png 1311868207.924004 depth/1311868207.924004.png
1311868207.973830 rgb/1311868207.973830.png 1311868207.988781 depth/1311868207.988781.png
1311868208.005771 rgb/1311868208.005771.png 1311868208.021627 depth/1311868208.021627.png
1311868208.037660 rgb/1311868208.037660.png 1311868208.056509 depth/1311868208.056509.png
1311868208.073670 rgb/1311868208.073670.png 1311868208.088991 depth/1311868208.088991.png
1311868208.137703 rgb/1311868208.137703.png 1311868208.123515 depth/1311868208.123515.png
1311868208.173832 rgb/1311868208.173832.png 1311868208.187911 depth/1311868208.187911.png
1311868208.237842 rgb/1311868208.237842.png 1311868208.223223 depth/1311868208.223223.png
1311868208.273904 rgb/1311868208.273904.png 1311868208.288012 depth/1311868208.288012.png
1311868208.337811 rgb/1311868208.337811.png 1311868208.324316 depth/1311868208.324316.png
1311868208.373775 rgb/1311868208.373775.png 1311868208.387355 depth/1311868208.387355.png
1311868208.437928 rgb/1311868208.437928.png 1311868208.424557 depth/1311868208.424557.png
1311868208.473867 rgb/1311868208.473867.png 1311868208.489116 depth/1311868208.489116.png
1311868208.537898 rgb/1311868208.537898.png 1311868208.527828 depth/1311868208.527828.png
1311868208.573867 rgb/1311868208.573867.png 1311868208.587870 depth/1311868208.587870.png
1311868208.637812 rgb/1311868208.637812.png 1311868208.623963 depth/1311868208.623963.png
1311868208.673890 rgb/1311868208.673890.png 1311868208.687952 depth/1311868208.687952.png
1311868208.737756 rgb/1311868208.737756.png 1311868208.723366 depth/1311868208.723366.png
1311868208.773982 rgb/1311868208.773982.png 1311868208.788388 depth/1311868208.788388.png
1311868208.837756 rgb/1311868208.837756.png 1311868208.824045 depth/1311868208.824045.png
1311868208.873831 rgb/1311868208.873831.png 1311868208.887440 depth/1311868208.887440.png
1311868208.937746 rgb/1311868208.937746.png 1311868208.923353 depth/1311868208.923353.png
1311868208.973765 rgb/1311868208.973765.png 1311868208.987749 depth/1311868208.987749.png
1311868209.037800 rgb/1311868209.037800.png 1311868209.023376 depth/1311868209.023376.png
1311868209.073793 rgb/1311868209.073793.png 1311868209.087996 depth/1311868209.087996.png
1311868209.137783 rgb/1311868209.137783.png 1311868209.124727 depth/1311868209.124727.png
1311868209.173775 rgb/1311868209.173775.png 1311868209.188268 depth/1311868209.188268.png
1311868209.237811 rgb/1311868209.237811.png 1311868209.223737 depth/1311868209.223737.png
1311868209.273776 rgb/1311868209.273776.png 1311868209.288996 depth/1311868209.288996.png
1311868209.305793 rgb/1311868209.305793.png 1311868209.324461 depth/1311868209.324461.png
1311868209.341866 rgb/1311868209.341866.png 1311868209.356288 depth/1311868209.356288.png
1311868209.405777 rgb/1311868209.405777.png 1311868209.397063 depth/1311868209.397063.png
1311868209.441953 rgb/1311868209.441953.png 1311868209.456861 depth/1311868209.456861.png
1311868209.505812 rgb/1311868209.505812.png 1311868209.492372 depth/1311868209.492372.png
1311868209.541800 rgb/1311868209.541800.png 1311868209.555981 depth/1311868209.555981.png
1311868209.606012 rgb/1311868209.606012.png 1311868209.592655 depth/1311868209.592655.png
1311868209.642092 rgb/1311868209.642092.png 1311868209.657089 depth/1311868209.657089.png
1311868209.705861 rgb/1311868209.705861.png 1311868209.693474 depth/1311868209.693474.png
1311868209.741975 rgb/1311868209.741975.png 1311868209.757140 depth/1311868209.757140.png
1311868209.805796 rgb/1311868209.805796.png 1311868209.793723 depth/1311868209.793723.png
1311868209.841897 rgb/1311868209.841897.png 1311868209.857383 depth/1311868209.857383.png
1311868209.905787 rgb/1311868209.905787.png 1311868209.891792 depth/1311868209.891792.png
1311868209.942127 rgb/1311868209.942127.png 1311868209.956558 depth/1311868209.956558.png
1311868210.005883 rgb/1311868210.005883.png 1311868209.991817 depth/1311868209.991817.png
1311868210.042009 rgb/1311868210.042009.png 1311868210.024765 depth/1311868210.024765.png
1311868210.073822 rgb/1311868210.073822.png 1311868210.058500 depth/1311868210.058500.png
1311868210.105867 rgb/1311868210.105867.png 1311868210.091532 depth/1311868210.091532.png
1311868210.141864 rgb/1311868210.141864.png 1311868210.123691 depth/1311868210.123691.png
1311868210.173922 rgb/1311868210.173922.png 1311868210.158032 depth/1311868210.158032.png
1311868210.205786 rgb/1311868210.205786.png 1311868210.193737 depth/1311868210.193737.png
1311868210.241903 rgb/1311868210.241903.png 1311868210.255458 depth/1311868210.255458.png
1311868210.305977 rgb/1311868210.305977.png 1311868210.292809 depth/1311868210.292809.png
1311868210.341851 rgb/1311868210.341851.png 1311868210.357061 depth/1311868210.357061.png
1311868210.405885 rgb/1311868210.405885.png 1311868210.391582 depth/1311868210.391582.png
1311868210.441961 rgb/1311868210.441961.png 1311868210.423315 depth/1311868210.423315.png
1311868210.473857 rgb/1311868210.473857.png 1311868210.459162 depth/1311868210.459162.png
1311868210.505879 rgb/1311868210.505879.png 1311868210.491729 depth/1311868210.491729.png
1311868210.541924 rgb/1311868210.541924.png 1311868210.524078 depth/1311868210.524078.png
1311868210.573923 rgb/1311868210.573923.png 1311868210.560350 depth/1311868210.560350.png
1311868210.605964 rgb/1311868210.605964.png 1311868210.593981 depth/1311868210.593981.png
1311868210.642018 rgb/1311868210.642018.png 1311868210.624137 depth/1311868210.624137.png
1311868210.673897 rgb/1311868210.673897.png 1311868210.660941 depth/1311868210.660941.png
1311868210.705897 rgb/1311868210.705897.png 1311868210.694072 depth/1311868210.694072.png
1311868210.742133 rgb/1311868210.742133.png 1311868210.725646 depth/1311868210.725646.png
1311868210.774018 rgb/1311868210.774018.png 1311868210.761375 depth/1311868210.761375.png
1311868210.805942 rgb/1311868210.805942.png 1311868210.792255 depth/1311868210.792255.png
1311868210.841882 rgb/1311868210.841882.png 1311868210.824869 depth/1311868210.824869.png
1311868210.873988 rgb/1311868210.873988.png 1311868210.862050 depth/1311868210.862050.png
1311868210.905826 rgb/1311868210.905826.png 1311868210.892741 depth/1311868210.892741.png
1311868210.942021 rgb/1311868210.942021.png 1311868210.925029 depth/1311868210.925029.png
1311868210.974235 rgb/1311868210.974235.png 1311868210.960048 depth/1311868210.960048.png
1311868211.005839 rgb/1311868211.005839.png 1311868210.993438 depth/1311868210.993438.png
1311868211.041878 rgb/1311868211.041878.png 1311868211.025176 depth/1311868211.025176.png
1311868211.074009 rgb/1311868211.074009.png 1311868211.059498 depth/1311868211.059498.png
1311868211.106006 rgb/1311868211.106006.png 1311868211.091740 depth/1311868211.091740.png
1311868211.142002 rgb/1311868211.142002.png 1311868211.125207 depth/1311868211.125207.png
1311868211.174051 rgb/1311868211.174051.png 1311868211.160225 depth/1311868211.160225.png
1311868211.205845 rgb/1311868211.205845.png 1311868211.192632 depth/1311868211.192632.png
1311868211.241987 rgb/1311868211.241987.png 1311868211.224527 depth/1311868211.224527.png
1311868211.274088 rgb/1311868211.274088.png 1311868211.259284 depth/1311868211.259284.png
1311868211.306090 rgb/1311868211.306090.png 1311868211.293066 depth/1311868211.293066.png
1311868211.342241 rgb/1311868211.342241.png 1311868211.324322 depth/1311868211.324322.png
1311868211.374052 rgb/1311868211.374052.png 1311868211.361163 depth/1311868211.361163.png
1311868211.406119 rgb/1311868211.406119.png 1311868211.393543 depth/1311868211.393543.png
1311868211.442216 rgb/1311868211.442216.png 1311868211.424189 depth/1311868211.424189.png
1311868211.473939 rgb/1311868211.473939.png 1311868211.460678 depth/1311868211.460678.png
1311868211.505937 rgb/1311868211.505937.png 1311868211.493996 depth/1311868211.493996.png
1311868211.541927 rgb/1311868211.541927.png 1311868211.524612 depth/1311868211.524612.png
1311868211.573950 rgb/1311868211.573950.png 1311868211.560741 depth/1311868211.560741.png
1311868211.606012 rgb/1311868211.606012.png 1311868211.592842 depth/1311868211.592842.png
1311868211.642009 rgb/1311868211.642009.png 1311868211.624034 depth/1311868211.624034.png
1311868211.674030 rgb/1311868211.674030.png 1311868211.659881 depth/1311868211.659881.png
1311868211.706002 rgb/1311868211.706002.png 1311868211.694654 depth/1311868211.694654.png
1311868211.742056 rgb/1311868211.742056.png 1311868211.724257 depth/1311868211.724257.png
1311868211.773982 rgb/1311868211.773982.png 1311868211.760756 depth/1311868211.760756.png
1311868211.806164 rgb/1311868211.806164.png 1311868211.796126 depth/1311868211.796126.png
1311868211.842132 rgb/1311868211.842132.png 1311868211.828952 depth/1311868211.828952.png
1311868211.873907 rgb/1311868211.873907.png 1311868211.861079 depth/1311868211.861079.png
1311868211.906024 rgb/1311868211.906024.png 1311868211.893028 depth/1311868211.893028.png
1311868211.942293 rgb/1311868211.942293.png 1311868211.928354 depth/1311868211.928354.png
1311868211.974041 rgb/1311868211.974041.png 1311868211.960968 depth/1311868211.960968.png
1311868212.005902 rgb/1311868212.005902.png 1311868211.994401 depth/1311868211.994401.png
1311868212.042182 rgb/1311868212.042182.png 1311868212.028849 depth/1311868212.028849.png
1311868212.074044 rgb/1311868212.074044.png 1311868212.062146 depth/1311868212.062146.png
1311868212.105906 rgb/1311868212.105906.png 1311868212.093919 depth/1311868212.093919.png
1311868212.142105 rgb/1311868212.142105.png 1311868212.127527 depth/1311868212.127527.png
1311868212.174023 rgb/1311868212.174023.png 1311868212.161612 depth/1311868212.161612.png
1311868212.206126 rgb/1311868212.206126.png 1311868212.194687 depth/1311868212.194687.png
1311868212.242313 rgb/1311868212.242313.png 1311868212.231541 depth/1311868212.231541.png
1311868212.274255 rgb/1311868212.274255.png 1311868212.262754 depth/1311868212.262754.png
1311868212.306028 rgb/1311868212.306028.png 1311868212.293996 depth/1311868212.293996.png
1311868212.342124 rgb/1311868212.342124.png 1311868212.327446 depth/1311868212.327446.png
1311868212.374157 rgb/1311868212.374157.png 1311868212.365707 depth/1311868212.365707.png
1311868212.406130 rgb/1311868212.406130.png 1311868212.391604 depth/1311868212.391604.png
1311868212.442138 rgb/1311868212.442138.png 1311868212.430051 depth/1311868212.430051.png
1311868212.474044 rgb/1311868212.474044.png 1311868212.465503 depth/1311868212.465503.png
1311868212.506032 rgb/1311868212.506032.png 1311868212.491652 depth/1311868212.491652.png
1311868212.542167 rgb/1311868212.542167.png 1311868212.527607 depth/1311868212.527607.png
1311868212.574023 rgb/1311868212.574023.png 1311868212.561717 depth/1311868212.561717.png
1311868212.606112 rgb/1311868212.606112.png 1311868212.596018 depth/1311868212.596018.png
1311868212.642096 rgb/1311868212.642096.png 1311868212.631003 depth/1311868212.631003.png
1311868212.674200 rgb/1311868212.674200.png 1311868212.662593 depth/1311868212.662593.png
1311868212.706878 rgb/1311868212.706878.png 1311868212.695112 depth/1311868212.695112.png
1311868212.742196 rgb/1311868212.742196.png 1311868212.731388 depth/1311868212.731388.png
1311868212.773943 rgb/1311868212.773943.png 1311868212.762764 depth/1311868212.762764.png
1311868212.806006 rgb/1311868212.806006.png 1311868212.793628 depth/1311868212.793628.png
1311868212.842064 rgb/1311868212.842064.png 1311868212.830201 depth/1311868212.830201.png
1311868212.874075 rgb/1311868212.874075.png 1311868212.861627 depth/1311868212.861627.png
1311868212.906161 rgb/1311868212.906161.png 1311868212.895707 depth/1311868212.895707.png
1311868212.942123 rgb/1311868212.942123.png 1311868212.930614 depth/1311868212.930614.png
1311868212.974154 rgb/1311868212.974154.png 1311868212.961582 depth/1311868212.961582.png
1311868213.006193 rgb/1311868213.006193.png 1311868212.995055 depth/1311868212.995055.png
1311868213.042223 rgb/1311868213.042223.png 1311868213.030994 depth/1311868213.030994.png
1311868213.073951 rgb/1311868213.073951.png 1311868213.062127 depth/1311868213.062127.png
1311868213.106053 rgb/1311868213.106053.png 1311868213.096720 depth/1311868213.096720.png
1311868213.142119 rgb/1311868213.142119.png 1311868213.130213 depth/1311868213.130213.png
1311868213.174219 rgb/1311868213.174219.png 1311868213.161672 depth/1311868213.161672.png
1311868213.206347 rgb/1311868213.206347.png 1311868213.199357 depth/1311868213.199357.png
1311868213.242209 rgb/1311868213.242209.png 1311868213.231589 depth/1311868213.231589.png
1311868213.274014 rgb/1311868213.274014.png 1311868213.262100 depth/1311868213.262100.png
1311868213.306151 rgb/1311868213.306151.png 1311868213.296404 depth/1311868213.296404.png
1311868213.342368 rgb/1311868213.342368.png 1311868213.331731 depth/1311868213.331731.png
1311868213.374390 rgb/1311868213.374390.png 1311868213.363191 depth/1311868213.363191.png
1311868213.406010 rgb/1311868213.406010.png 1311868213.395848 depth/1311868213.395848.png
1311868213.442300 rgb/1311868213.442300.png 1311868213.430986 depth/1311868213.430986.png
1311868213.474546 rgb/1311868213.474546.png 1311868213.463117 depth/1311868213.463117.png
1311868213.506347 rgb/1311868213.506347.png 1311868213.499324 depth/1311868213.499324.png
1311868213.542189 rgb/1311868213.542189.png 1311868213.531201 depth/1311868213.531201.png
1311868213.574297 rgb/1311868213.574297.png 1311868213.563046 depth/1311868213.563046.png
1311868213.608357 rgb/1311868213.608357.png 1311868213.599589 depth/1311868213.599589.png
1311868213.642086 rgb/1311868213.642086.png 1311868213.631001 depth/1311868213.631001.png
1311868213.674238 rgb/1311868213.674238.png 1311868213.661925 depth/1311868213.661925.png
1311868213.706267 rgb/1311868213.706267.png 1311868213.699582 depth/1311868213.699582.png
1311868213.742210 rgb/1311868213.742210.png 1311868213.729688 depth/1311868213.729688.png
1311868213.774084 rgb/1311868213.774084.png 1311868213.762865 depth/1311868213.762865.png
1311868213.806247 rgb/1311868213.806247.png 1311868213.798710 depth/1311868213.798710.png
1311868213.842211 rgb/1311868213.842211.png 1311868213.828307 depth/1311868213.828307.png
1311868213.874145 rgb/1311868213.874145.png 1311868213.862133 depth/1311868213.862133.png
1311868213.906335 rgb/1311868213.906335.png 1311868213.898969 depth/1311868213.898969.png
1311868213.942213 rgb/1311868213.942213.png 1311868213.932051 depth/1311868213.932051.png
1311868213.974085 rgb/1311868213.974085.png 1311868213.962376 depth/1311868213.962376.png
1311868214.006317 rgb/1311868214.006317.png 1311868214.000127 depth/1311868214.000127.png
1311868214.042178 rgb/1311868214.042178.png 1311868214.028718 depth/1311868214.028718.png
1311868214.074100 rgb/1311868214.074100.png 1311868214.062257 depth/1311868214.062257.png
1311868214.106187 rgb/1311868214.106187.png 1311868214.096212 depth/1311868214.096212.png
1311868214.142287 rgb/1311868214.142287.png 1311868214.130191 depth/1311868214.130191.png
1311868214.174039 rgb/1311868214.174039.png 1311868214.160358 depth/1311868214.160358.png
1311868214.206335 rgb/1311868214.206335.png 1311868214.196958 depth/1311868214.196958.png
1311868214.242159 rgb/1311868214.242159.png 1311868214.231385 depth/1311868214.231385.png
1311868214.274221 rgb/1311868214.274221.png 1311868214.269163 depth/1311868214.269163.png
1311868214.306406 rgb/1311868214.306406.png 1311868214.298875 depth/1311868214.298875.png
1311868214.342288 rgb/1311868214.342288.png 1311868214.331239 depth/1311868214.331239.png
1311868214.374244 rgb/1311868214.374244.png 1311868214.364089 depth/1311868214.364089.png
1311868214.406227 rgb/1311868214.406227.png 1311868214.400932 depth/1311868214.400932.png
1311868214.442184 rgb/1311868214.442184.png 1311868214.428342 depth/1311868214.428342.png
1311868214.474262 rgb/1311868214.474262.png 1311868214.466683 depth/1311868214.466683.png
1311868214.506579 rgb/1311868214.506579.png 1311868214.499607 depth/1311868214.499607.png
1311868214.542302 rgb/1311868214.542302.png 1311868214.531421 depth/1311868214.531421.png
1311868214.574356 rgb/1311868214.574356.png 1311868214.566788 depth/1311868214.566788.png
1311868214.606407 rgb/1311868214.606407.png 1311868214.596131 depth/1311868214.596131.png
1311868214.642280 rgb/1311868214.642280.png 1311868214.627964 depth/1311868214.627964.png
1311868214.674410 rgb/1311868214.674410.png 1311868214.667136 depth/1311868214.667136.png
1311868214.706198 rgb/1311868214.706198.png 1311868214.697712 depth/1311868214.697712.png
1311868214.742333 rgb/1311868214.742333.png 1311868214.727991 depth/1311868214.727991.png
1311868214.774481 rgb/1311868214.774481.png 1311868214.767288 depth/1311868214.767288.png
1311868214.806468 rgb/1311868214.806468.png 1311868214.798886 depth/1311868214.798886.png
1311868214.842297 rgb/1311868214.842297.png 1311868214.828913 depth/1311868214.828913.png
1311868214.874290 rgb/1311868214.874290.png 1311868214.868793 depth/1311868214.868793.png
1311868214.906326 rgb/1311868214.906326.png 1311868214.900436 depth/1311868214.900436.png
1311868214.942194 rgb/1311868214.942194.png 1311868214.927817 depth/1311868214.927817.png
1311868214.974404 rgb/1311868214.974404.png 1311868214.966937 depth/1311868214.966937.png
1311868215.006391 rgb/1311868215.006391.png 1311868214.999633 depth/1311868214.999633.png
1311868215.042220 rgb/1311868215.042220.png 1311868215.030933 depth/1311868215.030933.png
1311868215.074234 rgb/1311868215.074234.png 1311868215.064106 depth/1311868215.064106.png
1311868215.106202 rgb/1311868215.106202.png 1311868215.098227 depth/1311868215.098227.png
1311868215.142266 rgb/1311868215.142266.png 1311868215.129751 depth/1311868215.129751.png
1311868215.174343 rgb/1311868215.174343.png 1311868215.165719 depth/1311868215.165719.png
1311868215.206366 rgb/1311868215.206366.png 1311868215.199781 depth/1311868215.199781.png
1311868215.242259 rgb/1311868215.242259.png 1311868215.229628 depth/1311868215.229628.png
1311868215.274353 rgb/1311868215.274353.png 1311868215.265968 depth/1311868215.265968.png
1311868215.306401 rgb/1311868215.306401.png 1311868215.297820 depth/1311868215.297820.png
1311868215.342475 rgb/1311868215.342475.png 1311868215.331843 depth/1311868215.331843.png
1311868215.374240 rgb/1311868215.374240.png 1311868215.365828 depth/1311868215.365828.png
1311868215.406376 rgb/1311868215.406376.png 1311868215.398876 depth/1311868215.398876.png
1311868215.442338 rgb/1311868215.442338.png 1311868215.428227 depth/1311868215.428227.png
1311868215.474499 rgb/1311868215.474499.png 1311868215.464523 depth/1311868215.464523.png
1311868215.506308 rgb/1311868215.506308.png 1311868215.499379 depth/1311868215.499379.png
1311868215.542336 rgb/1311868215.542336.png 1311868215.532372 depth/1311868215.532372.png
1311868215.574139 rgb/1311868215.574139.png 1311868215.564697 depth/1311868215.564697.png
1311868215.606249 rgb/1311868215.606249.png 1311868215.595707 depth/1311868215.595707.png
1311868215.642404 rgb/1311868215.642404.png 1311868215.634840 depth/1311868215.634840.png
1311868215.674534 rgb/1311868215.674534.png 1311868215.666718 depth/1311868215.666718.png
1311868215.706473 rgb/1311868215.706473.png 1311868215.699219 depth/1311868215.699219.png
1311868215.742205 rgb/1311868215.742205.png 1311868215.733621 depth/1311868215.733621.png
1311868215.774735 rgb/1311868215.774735.png 1311868215.767615 depth/1311868215.767615.png
1311868215.806559 rgb/1311868215.806559.png 1311868215.801906 depth/1311868215.801906.png
1311868215.842289 rgb/1311868215.842289.png 1311868215.833568 depth/1311868215.833568.png
1311868215.874205 rgb/1311868215.874205.png 1311868215.864820 depth/1311868215.864820.png
1311868215.906403 rgb/1311868215.906403.png 1311868215.898023 depth/1311868215.898023.png
1311868215.942381 rgb/1311868215.942381.png 1311868215.932024 depth/1311868215.932024.png
1311868215.974271 rgb/1311868215.974271.png 1311868215.968317 depth/1311868215.968317.png
1311868216.006524 rgb/1311868216.006524.png 1311868215.996855 depth/1311868215.996855.png
1311868216.042488 rgb/1311868216.042488.png 1311868216.035046 depth/1311868216.035046.png
1311868216.074212 rgb/1311868216.074212.png 1311868216.065637 depth/1311868216.065637.png
1311868216.106321 rgb/1311868216.106321.png 1311868216.096071 depth/1311868216.096071.png
1311868216.142434 rgb/1311868216.142434.png 1311868216.135571 depth/1311868216.135571.png
1311868216.174227 rgb/1311868216.174227.png 1311868216.166199 depth/1311868216.166199.png
1311868216.206326 rgb/1311868216.206326.png 1311868216.197597 depth/1311868216.197597.png
1311868216.242946 rgb/1311868216.242946.png 1311868216.234802 depth/1311868216.234802.png
1311868216.275879 rgb/1311868216.275879.png 1311868216.266603 depth/1311868216.266603.png
1311868216.306682 rgb/1311868216.306682.png 1311868216.300423 depth/1311868216.300423.png
1311868216.342596 rgb/1311868216.342596.png 1311868216.334966 depth/1311868216.334966.png
1311868216.374273 rgb/1311868216.374273.png 1311868216.365042 depth/1311868216.365042.png
1311868216.406671 rgb/1311868216.406671.png 1311868216.396324 depth/1311868216.396324.png
1311868216.442339 rgb/1311868216.442339.png 1311868216.437861 depth/1311868216.437861.png
1311868216.474357 rgb/1311868216.474357.png 1311868216.464425 depth/1311868216.464425.png
1311868216.506418 rgb/1311868216.506418.png 1311868216.496861 depth/1311868216.496861.png
1311868216.542390 rgb/1311868216.542390.png 1311868216.531729 depth/1311868216.531729.png
1311868216.574328 rgb/1311868216.574328.png 1311868216.565989 depth/1311868216.565989.png
1311868216.606527 rgb/1311868216.606527.png 1311868216.597315 depth/1311868216.597315.png
1311868216.642461 rgb/1311868216.642461.png 1311868216.633797 depth/1311868216.633797.png
1311868216.674349 rgb/1311868216.674349.png 1311868216.665318 depth/1311868216.665318.png
1311868216.706576 rgb/1311868216.706576.png 1311868216.699687 depth/1311868216.699687.png
1311868216.742454 rgb/1311868216.742454.png 1311868216.732294 depth/1311868216.732294.png
1311868216.774257 rgb/1311868216.774257.png 1311868216.764468 depth/1311868216.764468.png
1311868216.806393 rgb/1311868216.806393.png 1311868216.800259 depth/1311868216.800259.png
1311868216.842459 rgb/1311868216.842459.png 1311868216.832619 depth/1311868216.832619.png
1311868216.874405 rgb/1311868216.874405.png 1311868216.866560 depth/1311868216.866560.png
1311868216.906366 rgb/1311868216.906366.png 1311868216.903003 depth/1311868216.903003.png
1311868216.942380 rgb/1311868216.942380.png 1311868216.932272 depth/1311868216.932272.png
1311868216.974559 rgb/1311868216.974559.png 1311868216.965458 depth/1311868216.965458.png
1311868217.006426 rgb/1311868217.006426.png 1311868217.002689 depth/1311868217.002689.png
1311868217.042435 rgb/1311868217.042435.png 1311868217.032318 depth/1311868217.032318.png
1311868217.074615 rgb/1311868217.074615.png 1311868217.065317 depth/1311868217.065317.png
1311868217.106679 rgb/1311868217.106679.png 1311868217.103305 depth/1311868217.103305.png
1311868217.143747 rgb/1311868217.143747.png 1311868217.136263 depth/1311868217.136263.png
1311868217.174613 rgb/1311868217.174613.png 1311868217.166840 depth/1311868217.166840.png
1311868217.206576 rgb/1311868217.206576.png 1311868217.201967 depth/1311868217.201967.png
1311868217.242361 rgb/1311868217.242361.png 1311868217.232198 depth/1311868217.232198.png
1311868217.274712 rgb/1311868217.274712.png 1311868217.266852 depth/1311868217.266852.png
1311868217.307288 rgb/1311868217.307288.png 1311868217.301319 depth/1311868217.301319.png
1311868217.342453 rgb/1311868217.342453.png 1311868217.332206 depth/1311868217.332206.png
1311868217.374311 rgb/1311868217.374311.png 1311868217.363769 depth/1311868217.363769.png
1311868217.406701 rgb/1311868217.406701.png 1311868217.399390 depth/1311868217.399390.png
1311868217.442485 rgb/1311868217.442485.png 1311868217.434691 depth/1311868217.434691.png
1311868217.475102 rgb/1311868217.475102.png 1311868217.466778 depth/1311868217.466778.png
1311868217.506647 rgb/1311868217.506647.png 1311868217.502605 depth/1311868217.502605.png
1311868217.542334 rgb/1311868217.542334.png 1311868217.531760 depth/1311868217.531760.png
1311868217.574294 rgb/1311868217.574294.png 1311868217.563694 depth/1311868217.563694.png
1311868217.606343 rgb/1311868217.606343.png 1311868217.599985 depth/1311868217.599985.png
1311868217.642399 rgb/1311868217.642399.png 1311868217.632879 depth/1311868217.632879.png
1311868217.674402 rgb/1311868217.674402.png 1311868217.664702 depth/1311868217.664702.png
1311868217.706372 rgb/1311868217.706372.png 1311868217.700189 depth/1311868217.700189.png
1311868217.742436 rgb/1311868217.742436.png 1311868217.735278 depth/1311868217.735278.png
1311868217.775482 rgb/1311868217.775482.png 1311868217.768408 depth/1311868217.768408.png
1311868217.806772 rgb/1311868217.806772.png 1311868217.801730 depth/1311868217.801730.png
1311868217.842462 rgb/1311868217.842462.png 1311868217.831781 depth/1311868217.831781.png
1311868217.874273 rgb/1311868217.874273.png 1311868217.866254 depth/1311868217.866254.png
1311868217.906458 rgb/1311868217.906458.png 1311868217.900688 depth/1311868217.900688.png
1311868217.942466 rgb/1311868217.942466.png 1311868217.935531 depth/1311868217.935531.png
1311868217.975110 rgb/1311868217.975110.png 1311868217.970178 depth/1311868217.970178.png
1311868218.006398 rgb/1311868218.006398.png 1311868217.999378 depth/1311868217.999378.png
1311868218.042374 rgb/1311868218.042374.png 1311868218.031505 depth/1311868218.031505.png
1311868218.074687 rgb/1311868218.074687.png 1311868218.067405 depth/1311868218.067405.png
1311868218.106528 rgb/1311868218.106528.png 1311868218.099367 depth/1311868218.099367.png
1311868218.142452 rgb/1311868218.142452.png 1311868218.131479 depth/1311868218.131479.png
1311868218.174634 rgb/1311868218.174634.png 1311868218.168288 depth/1311868218.168288.png
1311868218.206493 rgb/1311868218.206493.png 1311868218.199946 depth/1311868218.199946.png
1311868218.242489 rgb/1311868218.242489.png 1311868218.233668 depth/1311868218.233668.png
1311868218.274613 rgb/1311868218.274613.png 1311868218.270554 depth/1311868218.270554.png
1311868218.306510 rgb/1311868218.306510.png 1311868218.302471 depth/1311868218.302471.png
1311868218.342575 rgb/1311868218.342575.png 1311868218.333373 depth/1311868218.333373.png
1311868218.374760 rgb/1311868218.374760.png 1311868218.371327 depth/1311868218.371327.png
1311868218.410500 rgb/1311868218.410500.png 1311868218.405229 depth/1311868218.405229.png
1311868218.442486 rgb/1311868218.442486.png 1311868218.433451 depth/1311868218.433451.png
1311868218.474491 rgb/1311868218.474491.png 1311868218.472236 depth/1311868218.472236.png
1311868218.510448 rgb/1311868218.510448.png 1311868218.501503 depth/1311868218.501503.png
1311868218.542375 rgb/1311868218.542375.png 1311868218.532944 depth/1311868218.532944.png
1311868218.574422 rgb/1311868218.574422.png 1311868218.567444 depth/1311868218.567444.png
1311868218.610383 rgb/1311868218.610383.png 1311868218.602207 depth/1311868218.602207.png
1311868218.642508 rgb/1311868218.642508.png 1311868218.633787 depth/1311868218.633787.png
1311868218.674491 rgb/1311868218.674491.png 1311868218.667366 depth/1311868218.667366.png
1311868218.710423 rgb/1311868218.710423.png 1311868218.701368 depth/1311868218.701368.png
1311868218.742485 rgb/1311868218.742485.png 1311868218.732400 depth/1311868218.732400.png
1311868218.774455 rgb/1311868218.774455.png 1311868218.769072 depth/1311868218.769072.png
1311868218.810331 rgb/1311868218.810331.png 1311868218.800107 depth/1311868218.800107.png
1311868218.842407 rgb/1311868218.842407.png 1311868218.831723 depth/1311868218.831723.png
1311868218.874697 rgb/1311868218.874697.png 1311868218.869983 depth/1311868218.869983.png
1311868218.910344 rgb/1311868218.910344.png 1311868218.899595 depth/1311868218.899595.png
1311868218.942390 rgb/1311868218.942390.png 1311868218.931950 depth/1311868218.931950.png
1311868218.974531 rgb/1311868218.974531.png 1311868218.969948 depth/1311868218.969948.png
1311868219.010718 rgb/1311868219.010718.png 1311868219.001382 depth/1311868219.001382.png
1311868219.042799 rgb/1311868219.042799.png 1311868219.036519 depth/1311868219.036519.png
1311868219.074699 rgb/1311868219.074699.png 1311868219.067363 depth/1311868219.067363.png
1311868219.110710 rgb/1311868219.110710.png 1311868219.100346 depth/1311868219.100346.png
1311868219.142449 rgb/1311868219.142449.png 1311868219.132682 depth/1311868219.132682.png
1311868219.174460 rgb/1311868219.174460.png 1311868219.167726 depth/1311868219.167726.png
1311868219.210391 rgb/1311868219.210391.png 1311868219.199463 depth/1311868219.199463.png
1311868219.242632 rgb/1311868219.242632.png 1311868219.235734 depth/1311868219.235734.png
1311868219.274458 rgb/1311868219.274458.png 1311868219.267876 depth/1311868219.267876.png
1311868219.310567 rgb/1311868219.310567.png 1311868219.301405 depth/1311868219.301405.png
1311868219.342858 rgb/1311868219.342858.png 1311868219.336414 depth/1311868219.336414.png
1311868219.374565 rgb/1311868219.374565.png 1311868219.368069 depth/1311868219.368069.png
1311868219.410427 rgb/1311868219.410427.png 1311868219.400180 depth/1311868219.400180.png
1311868219.442491 rgb/1311868219.442491.png 1311868219.435990 depth/1311868219.435990.png
1311868219.474442 rgb/1311868219.474442.png 1311868219.467615 depth/1311868219.467615.png
1311868219.510471 rgb/1311868219.510471.png 1311868219.500250 depth/1311868219.500250.png
1311868219.543330 rgb/1311868219.543330.png 1311868219.540778 depth/1311868219.540778.png
1311868219.574798 rgb/1311868219.574798.png 1311868219.567933 depth/1311868219.567933.png
1311868219.610673 rgb/1311868219.610673.png 1311868219.602290 depth/1311868219.602290.png
1311868219.642931 rgb/1311868219.642931.png 1311868219.636093 depth/1311868219.636093.png
1311868219.674450 rgb/1311868219.674450.png 1311868219.667827 depth/1311868219.667827.png
1311868219.710785 rgb/1311868219.710785.png 1311868219.700080 depth/1311868219.700080.png
1311868219.742593 rgb/1311868219.742593.png 1311868219.735627 depth/1311868219.735627.png
1311868219.774534 rgb/1311868219.774534.png 1311868219.768145 depth/1311868219.768145.png
1311868219.810409 rgb/1311868219.810409.png 1311868219.801247 depth/1311868219.801247.png
1311868219.842777 rgb/1311868219.842777.png 1311868219.835981 depth/1311868219.835981.png
1311868219.874478 rgb/1311868219.874478.png 1311868219.867815 depth/1311868219.867815.png
1311868219.910641 rgb/1311868219.910641.png 1311868219.900014 depth/1311868219.900014.png
1311868219.942611 rgb/1311868219.942611.png 1311868219.936057 depth/1311868219.936057.png
1311868219.974873 rgb/1311868219.974873.png 1311868219.967731 depth/1311868219.967731.png
1311868220.010555 rgb/1311868220.010555.png 1311868220.000484 depth/1311868220.000484.png
1311868220.042788 rgb/1311868220.042788.png 1311868220.035991 depth/1311868220.035991.png
1311868220.074683 rgb/1311868220.074683.png 1311868220.068021 depth/1311868220.068021.png
1311868220.110558 rgb/1311868220.110558.png 1311868220.101658 depth/1311868220.101658.png
1311868220.142630 rgb/1311868220.142630.png 1311868220.136124 depth/1311868220.136124.png
1311868220.174706 rgb/1311868220.174706.png 1311868220.168106 depth/1311868220.168106.png
1311868220.210459 rgb/1311868220.210459.png 1311868220.200388 depth/1311868220.200388.png
1311868220.242513 rgb/1311868220.242513.png 1311868220.236348 depth/1311868220.236348.png
1311868220.274890 rgb/1311868220.274890.png 1311868220.268408 depth/1311868220.268408.png
1311868220.310675 rgb/1311868220.310675.png 1311868220.303243 depth/1311868220.303243.png
1311868220.342794 rgb/1311868220.342794.png 1311868220.336368 depth/1311868220.336368.png
1311868220.374967 rgb/1311868220.374967.png 1311868220.368106 depth/1311868220.368106.png
1311868220.410461 rgb/1311868220.410461.png 1311868220.400760 depth/1311868220.400760.png
1311868220.442609 rgb/1311868220.442609.png 1311868220.436414 depth/1311868220.436414.png
1311868220.474751 rgb/1311868220.474751.png 1311868220.468009 depth/1311868220.468009.png
1311868220.510865 rgb/1311868220.510865.png 1311868220.505404 depth/1311868220.505404.png
1311868220.542610 rgb/1311868220.542610.png 1311868220.535923 depth/1311868220.535923.png
1311868220.574495 rgb/1311868220.574495.png 1311868220.568743 depth/1311868220.568743.png
1311868220.611343 rgb/1311868220.611343.png 1311868220.607919 depth/1311868220.607919.png
1311868220.642648 rgb/1311868220.642648.png 1311868220.638122 depth/1311868220.638122.png
1311868220.674598 rgb/1311868220.674598.png 1311868220.669290 depth/1311868220.669290.png
1311868220.710604 rgb/1311868220.710604.png 1311868220.705802 depth/1311868220.705802.png
1311868220.742672 rgb/1311868220.742672.png 1311868220.740041 depth/1311868220.740041.png
1311868220.774530 rgb/1311868220.774530.png 1311868220.768076 depth/1311868220.768076.png
1311868220.810775 rgb/1311868220.810775.png 1311868220.807362 depth/1311868220.807362.png
1311868220.842747 rgb/1311868220.842747.png 1311868220.840215 depth/1311868220.840215.png
1311868220.874779 rgb/1311868220.874779.png 1311868220.868076 depth/1311868220.868076.png
1311868220.910650 rgb/1311868220.910650.png 1311868220.907645 depth/1311868220.907645.png
1311868220.942980 rgb/1311868220.942980.png 1311868220.936974 depth/1311868220.936974.png
1311868220.974895 rgb/1311868220.974895.png 1311868220.971264 depth/1311868220.971264.png
1311868221.010492 rgb/1311868221.010492.png 1311868221.004830 depth/1311868221.004830.png
1311868221.042575 rgb/1311868221.042575.png 1311868221.038022 depth/1311868221.038022.png
1311868221.074778 rgb/1311868221.074778.png 1311868221.068433 depth/1311868221.068433.png
1311868221.110563 rgb/1311868221.110563.png 1311868221.104071 depth/1311868221.104071.png
1311868221.142677 rgb/1311868221.142677.png 1311868221.136394 depth/1311868221.136394.png
1311868221.174633 rgb/1311868221.174633.png 1311868221.168289 depth/1311868221.168289.png
1311868221.210618 rgb/1311868221.210618.png 1311868221.208083 depth/1311868221.208083.png
1311868221.242676 rgb/1311868221.242676.png 1311868221.237782 depth/1311868221.237782.png
1311868221.274959 rgb/1311868221.274959.png 1311868221.270077 depth/1311868221.270077.png
1311868221.311415 rgb/1311868221.311415.png 1311868221.306408 depth/1311868221.306408.png
1311868221.342835 rgb/1311868221.342835.png 1311868221.336428 depth/1311868221.336428.png
1311868221.374902 rgb/1311868221.374902.png 1311868221.370085 depth/1311868221.370085.png
1311868221.410723 rgb/1311868221.410723.png 1311868221.407576 depth/1311868221.407576.png
1311868221.442831 rgb/1311868221.442831.png 1311868221.440279 depth/1311868221.440279.png
1311868221.474658 rgb/1311868221.474658.png 1311868221.470216 depth/1311868221.470216.png
1311868221.510999 rgb/1311868221.510999.png 1311868221.506155 depth/1311868221.506155.png
1311868221.543040 rgb/1311868221.543040.png 1311868221.539623 depth/1311868221.539623.png
1311868221.574743 rgb/1311868221.574743.png 1311868221.571188 depth/1311868221.571188.png
1311868221.610738 rgb/1311868221.610738.png 1311868221.606503 depth/1311868221.606503.png
1311868221.642622 rgb/1311868221.642622.png 1311868221.636216 depth/1311868221.636216.png
1311868221.674631 rgb/1311868221.674631.png 1311868221.673439 depth/1311868221.673439.png
1311868221.711507 rgb/1311868221.711507.png 1311868221.707091 depth/1311868221.707091.png
1311868221.742786 rgb/1311868221.742786.png 1311868221.738380 depth/1311868221.738380.png
1311868221.775854 rgb/1311868221.775854.png 1311868221.775869 depth/1311868221.775869.png
1311868221.810774 rgb/1311868221.810774.png 1311868221.805954 depth/1311868221.805954.png
1311868221.842668 rgb/1311868221.842668.png 1311868221.836585 depth/1311868221.836585.png
1311868221.874613 rgb/1311868221.874613.png 1311868221.873274 depth/1311868221.873274.png
1311868221.910793 rgb/1311868221.910793.png 1311868221.905122 depth/1311868221.905122.png
1311868221.942672 rgb/1311868221.942672.png 1311868221.936660 depth/1311868221.936660.png
1311868221.975288 rgb/1311868221.975288.png 1311868221.975301 depth/1311868221.975301.png
1311868222.010658 rgb/1311868222.010658.png 1311868222.006126 depth/1311868222.006126.png
1311868222.042799 rgb/1311868222.042799.png 1311868222.037887 depth/1311868222.037887.png
1311868222.077068 rgb/1311868222.077068.png 1311868222.077077 depth/1311868222.077077.png
1311868222.110687 rgb/1311868222.110687.png 1311868222.106238 depth/1311868222.106238.png
1311868222.142853 rgb/1311868222.142853.png 1311868222.136039 depth/1311868222.136039.png
1311868222.174994 rgb/1311868222.174994.png 1311868222.175004 depth/1311868222.175004.png
1311868222.210798 rgb/1311868222.210798.png 1311868222.204322 depth/1311868222.204322.png
1311868222.242692 rgb/1311868222.242692.png 1311868222.239963 depth/1311868222.239963.png
1311868222.275699 rgb/1311868222.275699.png 1311868222.275741 depth/1311868222.275741.png
1311868222.310861 rgb/1311868222.310861.png 1311868222.307107 depth/1311868222.307107.png
1311868222.343002 rgb/1311868222.343002.png 1311868222.337833 depth/1311868222.337833.png
1311868222.375332 rgb/1311868222.375332.png 1311868222.375382 depth/1311868222.375382.png
1311868222.410818 rgb/1311868222.410818.png 1311868222.407168 depth/1311868222.407168.png
1311868222.442701 rgb/1311868222.442701.png 1311868222.437456 depth/1311868222.437456.png
1311868222.474746 rgb/1311868222.474746.png 1311868222.474272 depth/1311868222.474272.png
1311868222.510786 rgb/1311868222.510786.png 1311868222.504091 depth/1311868222.504091.png
1311868222.542796 rgb/1311868222.542796.png 1311868222.536822 depth/1311868222.536822.png
1311868222.574664 rgb/1311868222.574664.png 1311868222.573445 depth/1311868222.573445.png
1311868222.610667 rgb/1311868222.610667.png 1311868222.606367 depth/1311868222.606367.png
1311868222.643013 rgb/1311868222.643013.png 1311868222.635993 depth/1311868222.635993.png
1311868222.674911 rgb/1311868222.674911.png 1311868222.674930 depth/1311868222.674930.png
1311868222.710764 rgb/1311868222.710764.png 1311868222.704440 depth/1311868222.704440.png
1311868222.742784 rgb/1311868222.742784.png 1311868222.737516 depth/1311868222.737516.png
1311868222.774863 rgb/1311868222.774863.png 1311868222.774872 depth/1311868222.774872.png
1311868222.810880 rgb/1311868222.810880.png 1311868222.804839 depth/1311868222.804839.png
1311868222.842888 rgb/1311868222.842888.png 1311868222.839765 depth/1311868222.839765.png
1311868222.875581 rgb/1311868222.875581.png 1311868222.875596 depth/1311868222.875596.png
1311868222.910730 rgb/1311868222.910730.png 1311868222.904031 depth/1311868222.904031.png
1311868222.943172 rgb/1311868222.943172.png 1311868222.943183 depth/1311868222.943183.png
1311868222.974842 rgb/1311868222.974842.png 1311868222.971964 depth/1311868222.971964.png
1311868223.012381 rgb/1311868223.012381.png 1311868223.007263 depth/1311868223.007263.png
1311868223.043777 rgb/1311868223.043777.png 1311868223.043787 depth/1311868223.043787.png
1311868223.076517 rgb/1311868223.076517.png 1311868223.076528 depth/1311868223.076528.png
1311868223.110921 rgb/1311868223.110921.png 1311868223.105782 depth/1311868223.105782.png
1311868223.143721 rgb/1311868223.143721.png 1311868223.143738 depth/1311868223.143738.png
1311868223.174769 rgb/1311868223.174769.png 1311868223.172518 depth/1311868223.172518.png
1311868223.210868 rgb/1311868223.210868.png 1311868223.207414 depth/1311868223.207414.png
1311868223.242696 rgb/1311868223.242696.png 1311868223.240462 depth/1311868223.240462.png
1311868223.275316 rgb/1311868223.275316.png 1311868223.275333 depth/1311868223.275333.png
1311868223.310697 rgb/1311868223.310697.png 1311868223.304131 depth/1311868223.304131.png
1311868223.343366 rgb/1311868223.343366.png 1311868223.343387 depth/1311868223.343387.png
1311868223.375535 rgb/1311868223.375535.png 1311868223.375547 depth/1311868223.375547.png
1311868223.410819 rgb/1311868223.410819.png 1311868223.404381 depth/1311868223.404381.png
1311868223.444149 rgb/1311868223.444149.png 1311868223.444168 depth/1311868223.444168.png
1311868223.479074 rgb/1311868223.479074.png 1311868223.479084 depth/1311868223.479084.png
1311868223.511227 rgb/1311868223.511227.png 1311868223.507287 depth/1311868223.507287.png
1311868223.542757 rgb/1311868223.542757.png 1311868223.541966 depth/1311868223.541966.png
1311868223.576261 rgb/1311868223.576261.png 1311868223.575255 depth/1311868223.575255.png
1311868223.610846 rgb/1311868223.610846.png 1311868223.607260 depth/1311868223.607260.png
1311868223.642738 rgb/1311868223.642738.png 1311868223.640714 depth/1311868223.640714.png
1311868223.674789 rgb/1311868223.674789.png 1311868223.672328 depth/1311868223.672328.png
1311868223.710948 rgb/1311868223.710948.png 1311868223.706442 depth/1311868223.706442.png
1311868223.742872 rgb/1311868223.742872.png 1311868223.740662 depth/1311868223.740662.png
1311868223.774925 rgb/1311868223.774925.png 1311868223.773620 depth/1311868223.773620.png
1311868223.810993 rgb/1311868223.810993.png 1311868223.804209 depth/1311868223.804209.png
1311868223.842828 rgb/1311868223.842828.png 1311868223.840316 depth/1311868223.840316.png
1311868223.874841 rgb/1311868223.874841.png 1311868223.872281 depth/1311868223.872281.png
1311868223.910906 rgb/1311868223.910906.png 1311868223.904377 depth/1311868223.904377.png
1311868223.943036 rgb/1311868223.943036.png 1311868223.943290 depth/1311868223.943290.png
1311868223.975101 rgb/1311868223.975101.png 1311868223.975108 depth/1311868223.975108.png
1311868224.010808 rgb/1311868224.010808.png 1311868224.007653 depth/1311868224.007653.png
1311868224.043743 rgb/1311868224.043743.png 1311868224.040432 depth/1311868224.040432.png
1311868224.075595 rgb/1311868224.075595.png 1311868224.075604 depth/1311868224.075604.png
1311868224.110830 rgb/1311868224.110830.png 1311868224.107394 depth/1311868224.107394.png
1311868224.145344 rgb/1311868224.145344.png 1311868224.145360 depth/1311868224.145360.png
1311868224.174788 rgb/1311868224.174788.png 1311868224.172734 depth/1311868224.172734.png
1311868224.211401 rgb/1311868224.211401.png 1311868224.211885 depth/1311868224.211885.png
1311868224.242911 rgb/1311868224.242911.png 1311868224.240252 depth/1311868224.240252.png
1311868224.277363 rgb/1311868224.277363.png 1311868224.273978 depth/1311868224.273978.png
1311868224.311516 rgb/1311868224.311516.png 1311868224.311536 depth/1311868224.311536.png
1311868224.342895 rgb/1311868224.342895.png 1311868224.340357 depth/1311868224.340357.png
1311868224.374897 rgb/1311868224.374897.png 1311868224.373499 depth/1311868224.373499.png
1311868224.410879 rgb/1311868224.410879.png 1311868224.408817 depth/1311868224.408817.png
1311868224.442907 rgb/1311868224.442907.png 1311868224.442917 depth/1311868224.442917.png
1311868224.474953 rgb/1311868224.474953.png 1311868224.472124 depth/1311868224.472124.png
1311868224.511812 rgb/1311868224.511812.png 1311868224.511856 depth/1311868224.511856.png
1311868224.545292 rgb/1311868224.545292.png 1311868224.545162 depth/1311868224.545162.png
1311868224.574703 rgb/1311868224.574703.png 1311868224.573673 depth/1311868224.573673.png
1311868224.611208 rgb/1311868224.611208.png 1311868224.611247 depth/1311868224.611247.png
1311868224.643090 rgb/1311868224.643090.png 1311868224.643159 depth/1311868224.643159.png
1311868224.674856 rgb/1311868224.674856.png 1311868224.672374 depth/1311868224.672374.png
1311868224.710776 rgb/1311868224.710776.png 1311868224.710056 depth/1311868224.710056.png
1311868224.742798 rgb/1311868224.742798.png 1311868224.740644 depth/1311868224.740644.png
1311868224.775598 rgb/1311868224.775598.png 1311868224.775615 depth/1311868224.775615.png
1311868224.812285 rgb/1311868224.812285.png 1311868224.812297 depth/1311868224.812297.png
1311868224.842708 rgb/1311868224.842708.png 1311868224.841945 depth/1311868224.841945.png
1311868224.874851 rgb/1311868224.874851.png 1311868224.874405 depth/1311868224.874405.png
1311868224.912106 rgb/1311868224.912106.png 1311868224.912116 depth/1311868224.912116.png
1311868224.943076 rgb/1311868224.943076.png 1311868224.940425 depth/1311868224.940425.png
1311868224.978324 rgb/1311868224.978324.png 1311868224.975279 depth/1311868224.975279.png
1311868225.012002 rgb/1311868225.012002.png 1311868225.012017 depth/1311868225.012017.png
1311868225.045354 rgb/1311868225.045354.png 1311868225.042544 depth/1311868225.042544.png
1311868225.076066 rgb/1311868225.076066.png 1311868225.076080 depth/1311868225.076080.png
1311868225.111236 rgb/1311868225.111236.png 1311868225.111317 depth/1311868225.111317.png
1311868225.143930 rgb/1311868225.143930.png 1311868225.143950 depth/1311868225.143950.png
1311868225.176049 rgb/1311868225.176049.png 1311868225.176066 depth/1311868225.176066.png
1311868225.211565 rgb/1311868225.211565.png 1311868225.209393 depth/1311868225.209393.png
1311868225.242896 rgb/1311868225.242896.png 1311868225.240636 depth/1311868225.240636.png
1311868225.275007 rgb/1311868225.275007.png 1311868225.275019 depth/1311868225.275019.png
1311868225.310787 rgb/1311868225.310787.png 1311868225.310797 depth/1311868225.310797.png
1311868225.342940 rgb/1311868225.342940.png 1311868225.340158 depth/1311868225.340158.png
1311868225.379392 rgb/1311868225.379392.png 1311868225.379405 depth/1311868225.379405.png
1311868225.410917 rgb/1311868225.410917.png 1311868225.410937 depth/1311868225.410937.png
1311868225.443381 rgb/1311868225.443381.png 1311868225.443405 depth/1311868225.443405.png
1311868225.479273 rgb/1311868225.479273.png 1311868225.479285 depth/1311868225.479285.png
1311868225.510884 rgb/1311868225.510884.png 1311868225.508380 depth/1311868225.508380.png
1311868225.542923 rgb/1311868225.542923.png 1311868225.541319 depth/1311868225.541319.png
1311868225.576439 rgb/1311868225.576439.png 1311868225.576451 depth/1311868225.576451.png
1311868225.612078 rgb/1311868225.612078.png 1311868225.612089 depth/1311868225.612089.png
1311868225.644151 rgb/1311868225.644151.png 1311868225.644160 depth/1311868225.644160.png
1311868225.678868 rgb/1311868225.678868.png 1311868225.678877 depth/1311868225.678877.png
1311868225.711259 rgb/1311868225.711259.png 1311868225.711272 depth/1311868225.711272.png
1311868225.746296 rgb/1311868225.746296.png 1311868225.746313 depth/1311868225.746313.png
1311868225.776898 rgb/1311868225.776898.png 1311868225.776903 depth/1311868225.776903.png
1311868225.810874 rgb/1311868225.810874.png 1311868225.810134 depth/1311868225.810134.png
1311868225.842939 rgb/1311868225.842939.png 1311868225.841916 depth/1311868225.841916.png
1311868225.880247 rgb/1311868225.880247.png 1311868225.880278 depth/1311868225.880278.png
1311868225.910765 rgb/1311868225.910765.png 1311868225.909912 depth/1311868225.909912.png
1311868225.943096 rgb/1311868225.943096.png 1311868225.943109 depth/1311868225.943109.png
1311868225.977018 rgb/1311868225.977018.png 1311868225.977027 depth/1311868225.977027.png
1311868226.010899 rgb/1311868226.010899.png 1311868226.008677 depth/1311868226.008677.png
1311868226.043782 rgb/1311868226.043782.png 1311868226.043800 depth/1311868226.043800.png
1311868226.079850 rgb/1311868226.079850.png 1311868226.079861 depth/1311868226.079861.png
1311868226.115058 rgb/1311868226.115058.png 1311868226.115075 depth/1311868226.115075.png
1311868226.144537 rgb/1311868226.144537.png 1311868226.144546 depth/1311868226.144546.png
1311868226.178896 rgb/1311868226.178896.png 1311868226.178910 depth/1311868226.178910.png
1311868226.210939 rgb/1311868226.210939.png 1311868226.210944 depth/1311868226.210944.png
1311868226.247306 rgb/1311868226.247306.png 1311868226.246456 depth/1311868226.246456.png
1311868226.277609 rgb/1311868226.277609.png 1311868226.277625 depth/1311868226.277625.png
1311868226.310950 rgb/1311868226.310950.png 1311868226.308469 depth/1311868226.308469.png
1311868226.345151 rgb/1311868226.345151.png 1311868226.345166 depth/1311868226.345166.png
1311868226.381607 rgb/1311868226.381607.png 1311868226.381651 depth/1311868226.381651.png
1311868226.411020 rgb/1311868226.411020.png 1311868226.408655 depth/1311868226.408655.png
1311868226.444052 rgb/1311868226.444052.png 1311868226.444073 depth/1311868226.444073.png
1311868226.481112 rgb/1311868226.481112.png 1311868226.481122 depth/1311868226.481122.png
1311868226.511027 rgb/1311868226.511027.png 1311868226.508358 depth/1311868226.508358.png
1311868226.543455 rgb/1311868226.543455.png 1311868226.546524 depth/1311868226.546524.png
1311868226.576612 rgb/1311868226.576612.png 1311868226.576639 depth/1311868226.576639.png
1311868226.610909 rgb/1311868226.610909.png 1311868226.610319 depth/1311868226.610319.png
1311868226.644260 rgb/1311868226.644260.png 1311868226.644264 depth/1311868226.644264.png
1311868226.676348 rgb/1311868226.676348.png 1311868226.676359 depth/1311868226.676359.png
1311868226.711126 rgb/1311868226.711126.png 1311868226.708363 depth/1311868226.708363.png
1311868226.745829 rgb/1311868226.745829.png 1311868226.745837 depth/1311868226.745837.png
1311868226.778492 rgb/1311868226.778492.png 1311868226.778507 depth/1311868226.778507.png
1311868226.810784 rgb/1311868226.810784.png 1311868226.809730 depth/1311868226.809730.png
1311868226.844284 rgb/1311868226.844284.png 1311868226.844289 depth/1311868226.844289.png
1311868226.879222 rgb/1311868226.879222.png 1311868226.879251 depth/1311868226.879251.png
1311868226.910863 rgb/1311868226.910863.png 1311868226.908253 depth/1311868226.908253.png
1311868226.944204 rgb/1311868226.944204.png 1311868226.944215 depth/1311868226.944215.png
1311868226.976309 rgb/1311868226.976309.png 1311868226.976315 depth/1311868226.976315.png
1311868227.010946 rgb/1311868227.010946.png 1311868227.010792 depth/1311868227.010792.png
1311868227.047092 rgb/1311868227.047092.png 1311868227.047113 depth/1311868227.047113.png
1311868227.077103 rgb/1311868227.077103.png 1311868227.077119 depth/1311868227.077119.png
1311868227.110902 rgb/1311868227.110902.png 1311868227.109667 depth/1311868227.109667.png
1311868227.144535 rgb/1311868227.144535.png 1311868227.144548 depth/1311868227.144548.png
1311868227.179137 rgb/1311868227.179137.png 1311868227.179146 depth/1311868227.179146.png
1311868227.210865 rgb/1311868227.210865.png 1311868227.209760 depth/1311868227.209760.png
1311868227.247413 rgb/1311868227.247413.png 1311868227.247444 depth/1311868227.247444.png
1311868227.276556 rgb/1311868227.276556.png 1311868227.276576 depth/1311868227.276576.png
1311868227.311677 rgb/1311868227.311677.png 1311868227.311685 depth/1311868227.311685.png
1311868227.347893 rgb/1311868227.347893.png 1311868227.347925 depth/1311868227.347925.png
1311868227.377762 rgb/1311868227.377762.png 1311868227.377769 depth/1311868227.377769.png
1311868227.411422 rgb/1311868227.411422.png 1311868227.411441 depth/1311868227.411441.png
1311868227.446682 rgb/1311868227.446682.png 1311868227.446700 depth/1311868227.446700.png
1311868227.479018 rgb/1311868227.479018.png 1311868227.476734 depth/1311868227.476734.png
1311868227.510861 rgb/1311868227.510861.png 1311868227.509621 depth/1311868227.509621.png
1311868227.547438 rgb/1311868227.547438.png 1311868227.547447 depth/1311868227.547447.png
1311868227.579073 rgb/1311868227.579073.png 1311868227.576509 depth/1311868227.576509.png
1311868227.610890 rgb/1311868227.610890.png 1311868227.610169 depth/1311868227.610169.png
1311868227.644341 rgb/1311868227.644341.png 1311868227.644352 depth/1311868227.644352.png
1311868227.679026 rgb/1311868227.679026.png 1311868227.676558 depth/1311868227.676558.png
1311868227.711001 rgb/1311868227.711001.png 1311868227.708818 depth/1311868227.708818.png
1311868227.744281 rgb/1311868227.744281.png 1311868227.744295 depth/1311868227.744295.png
1311868227.779154 rgb/1311868227.779154.png 1311868227.776629 depth/1311868227.776629.png
1311868227.813722 rgb/1311868227.813722.png 1311868227.813739 depth/1311868227.813739.png
1311868227.844330 rgb/1311868227.844330.png 1311868227.844235 depth/1311868227.844235.png
1311868227.879151 rgb/1311868227.879151.png 1311868227.876400 depth/1311868227.876400.png
1311868227.912471 rgb/1311868227.912471.png 1311868227.912496 depth/1311868227.912496.png
1311868227.946163 rgb/1311868227.946163.png 1311868227.946174 depth/1311868227.946174.png
1311868227.979289 rgb/1311868227.979289.png 1311868227.979307 depth/1311868227.979307.png
1311868228.014729 rgb/1311868228.014729.png 1311868228.014743 depth/1311868228.014743.png
1311868228.044938 rgb/1311868228.044938.png 1311868228.044945 depth/1311868228.044945.png
1311868228.079022 rgb/1311868228.079022.png 1311868228.079040 depth/1311868228.079040.png
1311868228.112684 rgb/1311868228.112684.png 1311868228.112696 depth/1311868228.112696.png
1311868228.146187 rgb/1311868228.146187.png 1311868228.146245 depth/1311868228.146245.png
1311868228.178968 rgb/1311868228.178968.png 1311868228.177569 depth/1311868228.177569.png
1311868228.214746 rgb/1311868228.214746.png 1311868228.214818 depth/1311868228.214818.png
1311868228.246147 rgb/1311868228.246147.png 1311868228.246155 depth/1311868228.246155.png
1311868228.279971 rgb/1311868228.279971.png 1311868228.277518 depth/1311868228.277518.png
1311868228.312417 rgb/1311868228.312417.png 1311868228.312426 depth/1311868228.312426.png
1311868228.344381 rgb/1311868228.344381.png 1311868228.344411 depth/1311868228.344411.png
1311868228.378967 rgb/1311868228.378967.png 1311868228.378082 depth/1311868228.378082.png
1311868228.412437 rgb/1311868228.412437.png 1311868228.412447 depth/1311868228.412447.png
1311868228.444527 rgb/1311868228.444527.png 1311868228.444535 depth/1311868228.444535.png
1311868228.479553 rgb/1311868228.479553.png 1311868228.477488 depth/1311868228.477488.png
1311868228.515154 rgb/1311868228.515154.png 1311868228.515164 depth/1311868228.515164.png
1311868228.545801 rgb/1311868228.545801.png 1311868228.545809 depth/1311868228.545809.png
1311868228.579592 rgb/1311868228.579592.png 1311868228.576548 depth/1311868228.576548.png
1311868228.612450 rgb/1311868228.612450.png 1311868228.613103 depth/1311868228.613103.png
1311868228.645315 rgb/1311868228.645315.png 1311868228.645326 depth/1311868228.645326.png
1311868228.679035 rgb/1311868228.679035.png 1311868228.678198 depth/1311868228.678198.png
1311868228.714922 rgb/1311868228.714922.png 1311868228.714943 depth/1311868228.714943.png
1311868228.746541 rgb/1311868228.746541.png 1311868228.746562 depth/1311868228.746562.png
1311868228.779112 rgb/1311868228.779112.png 1311868228.776419 depth/1311868228.776419.png
1311868228.815012 rgb/1311868228.815012.png 1311868228.815023 depth/1311868228.815023.png
1311868228.844666 rgb/1311868228.844666.png 1311868228.844682 depth/1311868228.844682.png
1311868228.879273 rgb/1311868228.879273.png 1311868228.876855 depth/1311868228.876855.png
1311868228.912667 rgb/1311868228.912667.png 1311868228.912678 depth/1311868228.912678.png
1311868228.944678 rgb/1311868228.944678.png 1311868228.944686 depth/1311868228.944686.png
1311868228.979108 rgb/1311868228.979108.png 1311868228.976767 depth/1311868228.976767.png
1311868229.012685 rgb/1311868229.012685.png 1311868229.012705 depth/1311868229.012705.png
1311868229.044504 rgb/1311868229.044504.png 1311868229.044519 depth/1311868229.044519.png
1311868229.080635 rgb/1311868229.080635.png 1311868229.080644 depth/1311868229.080644.png
1311868229.115479 rgb/1311868229.115479.png 1311868229.115079 depth/1311868229.115079.png
1311868229.148295 rgb/1311868229.148295.png 1311868229.148304 depth/1311868229.148304.png
1311868229.184081 rgb/1311868229.184081.png 1311868229.184100 depth/1311868229.184100.png
1311868229.216477 rgb/1311868229.216477.png 1311868229.216508 depth/1311868229.216508.png
1311868229.249047 rgb/1311868229.249047.png 1311868229.249184 depth/1311868229.249184.png
1311868229.281198 rgb/1311868229.281198.png 1311868229.281306 depth/1311868229.281306.png
1311868229.315238 rgb/1311868229.315238.png 1311868229.315247 depth/1311868229.315247.png
1311868229.350313 rgb/1311868229.350313.png 1311868229.345007 depth/1311868229.345007.png
1311868229.381047 rgb/1311868229.381047.png 1311868229.381055 depth/1311868229.381055.png
1311868229.413148 rgb/1311868229.413148.png 1311868229.413156 depth/1311868229.413156.png
1311868229.444833 rgb/1311868229.444833.png 1311868229.444845 depth/1311868229.444845.png
1311868229.482439 rgb/1311868229.482439.png 1311868229.482317 depth/1311868229.482317.png
1311868229.512638 rgb/1311868229.512638.png 1311868229.512643 depth/1311868229.512643.png
1311868229.547820 rgb/1311868229.547820.png 1311868229.547829 depth/1311868229.547829.png
1311868229.580641 rgb/1311868229.580641.png 1311868229.580649 depth/1311868229.580649.png
1311868229.613429 rgb/1311868229.613429.png 1311868229.613438 depth/1311868229.613438.png
1311868229.647479 rgb/1311868229.647479.png 1311868229.647491 depth/1311868229.647491.png
1311868229.681523 rgb/1311868229.681523.png 1311868229.681542 depth/1311868229.681542.png
1311868229.712459 rgb/1311868229.712459.png 1311868229.712514 depth/1311868229.712514.png
1311868229.748721 rgb/1311868229.748721.png 1311868229.748851 depth/1311868229.748851.png
1311868229.782489 rgb/1311868229.782489.png 1311868229.782512 depth/1311868229.782512.png
1311868229.812669 rgb/1311868229.812669.png 1311868229.812710 depth/1311868229.812710.png
1311868229.844489 rgb/1311868229.844489.png 1311868229.844496 depth/1311868229.844496.png
1311868229.883361 rgb/1311868229.883361.png 1311868229.883367 depth/1311868229.883367.png
1311868229.914462 rgb/1311868229.914462.png 1311868229.914473 depth/1311868229.914473.png
1311868229.944417 rgb/1311868229.944417.png 1311868229.944425 depth/1311868229.944425.png
1311868229.982424 rgb/1311868229.982424.png 1311868229.982447 depth/1311868229.982447.png
1311868230.012490 rgb/1311868230.012490.png 1311868230.012502 depth/1311868230.012502.png
1311868230.047030 rgb/1311868230.047030.png 1311868230.047041 depth/1311868230.047041.png
1311868230.083190 rgb/1311868230.083190.png 1311868230.083195 depth/1311868230.083195.png
1311868230.113585 rgb/1311868230.113585.png 1311868230.113593 depth/1311868230.113593.png
1311868230.147393 rgb/1311868230.147393.png 1311868230.147405 depth/1311868230.147405.png
1311868230.180570 rgb/1311868230.180570.png 1311868230.180580 depth/1311868230.180580.png
1311868230.214879 rgb/1311868230.214879.png 1311868230.214916 depth/1311868230.214916.png
1311868230.245363 rgb/1311868230.245363.png 1311868230.245372 depth/1311868230.245372.png
1311868230.283031 rgb/1311868230.283031.png 1311868230.283053 depth/1311868230.283053.png
1311868230.312518 rgb/1311868230.312518.png 1311868230.312531 depth/1311868230.312531.png
1311868230.343265 rgb/1311868230.343265.png 1311868230.353156 depth/1311868230.353156.png
1311868230.382061 rgb/1311868230.382061.png 1311868230.382076 depth/1311868230.382076.png
1311868230.414198 rgb/1311868230.414198.png 1311868230.414216 depth/1311868230.414216.png
1311868230.443234 rgb/1311868230.443234.png 1311868230.450510 depth/1311868230.450510.png
1311868230.484314 rgb/1311868230.484314.png 1311868230.484325 depth/1311868230.484325.png
1311868230.512705 rgb/1311868230.512705.png 1311868230.512945 depth/1311868230.512945.png
1311868230.543330 rgb/1311868230.543330.png 1311868230.549719 depth/1311868230.549719.png
1311868230.582035 rgb/1311868230.582035.png 1311868230.582042 depth/1311868230.582042.png
1311868230.613609 rgb/1311868230.613609.png 1311868230.613625 depth/1311868230.613625.png
1311868230.643420 rgb/1311868230.643420.png 1311868230.649952 depth/1311868230.649952.png
1311868230.682847 rgb/1311868230.682847.png 1311868230.682859 depth/1311868230.682859.png
1311868230.713079 rgb/1311868230.713079.png 1311868230.713087 depth/1311868230.713087.png
1311868230.743239 rgb/1311868230.743239.png 1311868230.752279 depth/1311868230.752279.png
1311868230.783163 rgb/1311868230.783163.png 1311868230.783179 depth/1311868230.783179.png
1311868230.812536 rgb/1311868230.812536.png 1311868230.812551 depth/1311868230.812551.png
1311868230.843194 rgb/1311868230.843194.png 1311868230.849972 depth/1311868230.849972.png
1311868230.884514 rgb/1311868230.884514.png 1311868230.884557 depth/1311868230.884557.png
1311868230.912835 rgb/1311868230.912835.png 1311868230.912844 depth/1311868230.912844.png
1311868230.943429 rgb/1311868230.943429.png 1311868230.950464 depth/1311868230.950464.png
1311868230.983928 rgb/1311868230.983928.png 1311868230.983939 depth/1311868230.983939.png
1311868231.012678 rgb/1311868231.012678.png 1311868231.012688 depth/1311868231.012688.png
1311868231.043362 rgb/1311868231.043362.png 1311868231.053257 depth/1311868231.053257.png
1311868231.083967 rgb/1311868231.083967.png 1311868231.083982 depth/1311868231.083982.png
1311868231.115505 rgb/1311868231.115505.png 1311868231.115521 depth/1311868231.115521.png
1311868231.143191 rgb/1311868231.143191.png 1311868231.150642 depth/1311868231.150642.png
1311868231.180564 rgb/1311868231.180564.png 1311868231.180574 depth/1311868231.180574.png
1311868231.215427 rgb/1311868231.215427.png 1311868231.215437 depth/1311868231.215437.png
1311868231.243144 rgb/1311868231.243144.png 1311868231.251532 depth/1311868231.251532.png
1311868231.284432 rgb/1311868231.284432.png 1311868231.284151 depth/1311868231.284151.png
1311868231.313322 rgb/1311868231.313322.png 1311868231.313332 depth/1311868231.313332.png
1311868231.343237 rgb/1311868231.343237.png 1311868231.350818 depth/1311868231.350818.png
1311868231.380706 rgb/1311868231.380706.png 1311868231.385816 depth/1311868231.385816.png
1311868231.412886 rgb/1311868231.412886.png 1311868231.412906 depth/1311868231.412906.png
1311868231.443247 rgb/1311868231.443247.png 1311868231.451469 depth/1311868231.451469.png
1311868231.481615 rgb/1311868231.481615.png 1311868231.481626 depth/1311868231.481626.png
1311868231.514222 rgb/1311868231.514222.png 1311868231.514232 depth/1311868231.514232.png
1311868231.543183 rgb/1311868231.543183.png 1311868231.551045 depth/1311868231.551045.png
1311868231.582970 rgb/1311868231.582970.png 1311868231.582981 depth/1311868231.582981.png
1311868231.611182 rgb/1311868231.611182.png 1311868231.616852 depth/1311868231.616852.png
1311868231.643249 rgb/1311868231.643249.png 1311868231.650892 depth/1311868231.650892.png
1311868231.683851 rgb/1311868231.683851.png 1311868231.683868 depth/1311868231.683868.png
1311868231.711268 rgb/1311868231.711268.png 1311868231.718914 depth/1311868231.718914.png
1311868231.743341 rgb/1311868231.743341.png 1311868231.749256 depth/1311868231.749256.png
1311868231.782700 rgb/1311868231.782700.png 1311868231.782718 depth/1311868231.782718.png
1311868231.811225 rgb/1311868231.811225.png 1311868231.817512 depth/1311868231.817512.png
1311868231.843239 rgb/1311868231.843239.png 1311868231.848763 depth/1311868231.848763.png
1311868231.883453 rgb/1311868231.883453.png 1311868231.883462 depth/1311868231.883462.png
1311868231.911236 rgb/1311868231.911236.png 1311868231.917510 depth/1311868231.917510.png
1311868231.943245 rgb/1311868231.943245.png 1311868231.949859 depth/1311868231.949859.png
1311868231.981369 rgb/1311868231.981369.png 1311868231.981380 depth/1311868231.981380.png
1311868232.011255 rgb/1311868232.011255.png 1311868232.019822 depth/1311868232.019822.png
1311868232.043334 rgb/1311868232.043334.png 1311868232.053452 depth/1311868232.053452.png
1311868232.084470 rgb/1311868232.084470.png 1311868232.082697 depth/1311868232.082697.png
1311868232.111198 rgb/1311868232.111198.png 1311868232.117808 depth/1311868232.117808.png
1311868232.143235 rgb/1311868232.143235.png 1311868232.150460 depth/1311868232.150460.png
1311868232.180728 rgb/1311868232.180728.png 1311868232.180762 depth/1311868232.180762.png
1311868232.211380 rgb/1311868232.211380.png 1311868232.220546 depth/1311868232.220546.png
1311868232.243208 rgb/1311868232.243208.png 1311868232.250282 depth/1311868232.250282.png
1311868232.280974 rgb/1311868232.280974.png 1311868232.280983 depth/1311868232.280983.png
1311868232.311279 rgb/1311868232.311279.png 1311868232.318613 depth/1311868232.318613.png
1311868232.343193 rgb/1311868232.343193.png 1311868232.349347 depth/1311868232.349347.png
1311868232.380596 rgb/1311868232.380596.png 1311868232.380604 depth/1311868232.380604.png
1311868232.411402 rgb/1311868232.411402.png 1311868232.417365 depth/1311868232.417365.png
1311868232.443259 rgb/1311868232.443259.png 1311868232.449624 depth/1311868232.449624.png
1311868232.482622 rgb/1311868232.482622.png 1311868232.482363 depth/1311868232.482363.png
1311868232.511307 rgb/1311868232.511307.png 1311868232.517622 depth/1311868232.517622.png
1311868232.543326 rgb/1311868232.543326.png 1311868232.549644 depth/1311868232.549644.png
1311868232.583131 rgb/1311868232.583131.png 1311868232.583150 depth/1311868232.583150.png
1311868232.611461 rgb/1311868232.611461.png 1311868232.618049 depth/1311868232.618049.png
1311868232.643442 rgb/1311868232.643442.png 1311868232.651240 depth/1311868232.651240.png
1311868232.683408 rgb/1311868232.683408.png 1311868232.683275 depth/1311868232.683275.png
1311868232.711301 rgb/1311868232.711301.png 1311868232.717433 depth/1311868232.717433.png
1311868232.744002 rgb/1311868232.744002.png 1311868232.760567 depth/1311868232.760567.png
1311868232.779268 rgb/1311868232.779268.png 1311868232.788795 depth/1311868232.788795.png
1311868232.811594 rgb/1311868232.811594.png 1311868232.821899 depth/1311868232.821899.png
1311868232.843289 rgb/1311868232.843289.png 1311868232.849796 depth/1311868232.849796.png
1311868232.879421 rgb/1311868232.879421.png 1311868232.886899 depth/1311868232.886899.png
1311868232.911483 rgb/1311868232.911483.png 1311868232.917623 depth/1311868232.917623.png
1311868232.943301 rgb/1311868232.943301.png 1311868232.950276 depth/1311868232.950276.png
1311868232.979469 rgb/1311868232.979469.png 1311868232.988268 depth/1311868232.988268.png
1311868233.011303 rgb/1311868233.011303.png 1311868233.017130 depth/1311868233.017130.png
1311868233.043607 rgb/1311868233.043607.png 1311868233.053790 depth/1311868233.053790.png
1311868233.079646 rgb/1311868233.079646.png 1311868233.087365 depth/1311868233.087365.png
1311868233.111321 rgb/1311868233.111321.png 1311868233.120528 depth/1311868233.120528.png
1311868233.143478 rgb/1311868233.143478.png 1311868233.150808 depth/1311868233.150808.png
1311868233.179701 rgb/1311868233.179701.png 1311868233.190997 depth/1311868233.190997.png
1311868233.211366 rgb/1311868233.211366.png 1311868233.217818 depth/1311868233.217818.png
1311868233.243606 rgb/1311868233.243606.png 1311868233.255486 depth/1311868233.255486.png
1311868233.279654 rgb/1311868233.279654.png 1311868233.286477 depth/1311868233.286477.png
1311868233.311396 rgb/1311868233.311396.png 1311868233.317556 depth/1311868233.317556.png
1311868233.343465 rgb/1311868233.343465.png 1311868233.351808 depth/1311868233.351808.png
1311868233.379449 rgb/1311868233.379449.png 1311868233.389965 depth/1311868233.389965.png
1311868233.411418 rgb/1311868233.411418.png 1311868233.423306 depth/1311868233.423306.png
1311868233.443336 rgb/1311868233.443336.png 1311868233.450921 depth/1311868233.450921.png
1311868233.479382 rgb/1311868233.479382.png 1311868233.487479 depth/1311868233.487479.png
1311868233.511408 rgb/1311868233.511408.png 1311868233.519239 depth/1311868233.519239.png
1311868233.543443 rgb/1311868233.543443.png 1311868233.552597 depth/1311868233.552597.png
1311868233.579545 rgb/1311868233.579545.png 1311868233.588303 depth/1311868233.588303.png
1311868233.611453 rgb/1311868233.611453.png 1311868233.622230 depth/1311868233.622230.png
1311868233.643320 rgb/1311868233.643320.png 1311868233.650993 depth/1311868233.650993.png
1311868233.679470 rgb/1311868233.679470.png 1311868233.691955 depth/1311868233.691955.png
1311868233.711536 rgb/1311868233.711536.png 1311868233.720779 depth/1311868233.720779.png
1311868233.743366 rgb/1311868233.743366.png 1311868233.751733 depth/1311868233.751733.png
1311868233.779597 rgb/1311868233.779597.png 1311868233.787975 depth/1311868233.787975.png
1311868233.811509 rgb/1311868233.811509.png 1311868233.818118 depth/1311868233.818118.png
1311868233.843614 rgb/1311868233.843614.png 1311868233.851616 depth/1311868233.851616.png
1311868233.879475 rgb/1311868233.879475.png 1311868233.889151 depth/1311868233.889151.png
1311868233.911537 rgb/1311868233.911537.png 1311868233.923064 depth/1311868233.923064.png
1311868233.943472 rgb/1311868233.943472.png 1311868233.955333 depth/1311868233.955333.png
1311868233.979347 rgb/1311868233.979347.png 1311868233.986443 depth/1311868233.986443.png
1311868234.011459 rgb/1311868234.011459.png 1311868234.021528 depth/1311868234.021528.png
1311868234.043413 rgb/1311868234.043413.png 1311868234.056173 depth/1311868234.056173.png
1311868234.079556 rgb/1311868234.079556.png 1311868234.088018 depth/1311868234.088018.png
1311868234.111633 rgb/1311868234.111633.png 1311868234.119824 depth/1311868234.119824.png
1311868234.143456 rgb/1311868234.143456.png 1311868234.158777 depth/1311868234.158777.png
1311868234.179448 rgb/1311868234.179448.png 1311868234.190031 depth/1311868234.190031.png
1311868234.211483 rgb/1311868234.211483.png 1311868234.217779 depth/1311868234.217779.png
1311868234.243581 rgb/1311868234.243581.png 1311868234.260062 depth/1311868234.260062.png
1311868234.279402 rgb/1311868234.279402.png 1311868234.288925 depth/1311868234.288925.png
1311868234.311515 rgb/1311868234.311515.png 1311868234.317660 depth/1311868234.317660.png
1311868234.343505 rgb/1311868234.343505.png 1311868234.358032 depth/1311868234.358032.png
1311868234.379573 rgb/1311868234.379573.png 1311868234.387788 depth/1311868234.387788.png
1311868234.411591 rgb/1311868234.411591.png 1311868234.420269 depth/1311868234.420269.png
1311868234.443480 rgb/1311868234.443480.png 1311868234.458374 depth/1311868234.458374.png
1311868234.479529 rgb/1311868234.479529.png 1311868234.489425 depth/1311868234.489425.png
1311868234.511642 rgb/1311868234.511642.png 1311868234.522233 depth/1311868234.522233.png
1311868234.543567 rgb/1311868234.543567.png 1311868234.555122 depth/1311868234.555122.png
1311868234.579412 rgb/1311868234.579412.png 1311868234.585931 depth/1311868234.585931.png
1311868234.611718 rgb/1311868234.611718.png 1311868234.622267 depth/1311868234.622267.png
1311868234.643547 rgb/1311868234.643547.png 1311868234.659470 depth/1311868234.659470.png
1311868234.679531 rgb/1311868234.679531.png 1311868234.687519 depth/1311868234.687519.png
1311868234.711442 rgb/1311868234.711442.png 1311868234.719153 depth/1311868234.719153.png
1311868234.743637 rgb/1311868234.743637.png 1311868234.758006 depth/1311868234.758006.png
1311868234.779522 rgb/1311868234.779522.png 1311868234.787070 depth/1311868234.787070.png
1311868234.811711 rgb/1311868234.811711.png 1311868234.822201 depth/1311868234.822201.png
1311868234.843512 rgb/1311868234.843512.png 1311868234.859209 depth/1311868234.859209.png
1311868234.879399 rgb/1311868234.879399.png 1311868234.888554 depth/1311868234.888554.png
1311868234.911468 rgb/1311868234.911468.png 1311868234.920603 depth/1311868234.920603.png
1311868234.943562 rgb/1311868234.943562.png 1311868234.957717 depth/1311868234.957717.png
1311868234.979489 rgb/1311868234.979489.png 1311868234.986417 depth/1311868234.986417.png
1311868235.011644 rgb/1311868235.011644.png 1311868235.023210 depth/1311868235.023210.png
1311868235.043680 rgb/1311868235.043680.png 1311868235.059341 depth/1311868235.059341.png
1311868235.079664 rgb/1311868235.079664.png 1311868235.087705 depth/1311868235.087705.png
1311868235.111629 rgb/1311868235.111629.png 1311868235.122347 depth/1311868235.122347.png
1311868235.143595 rgb/1311868235.143595.png 1311868235.156195 depth/1311868235.156195.png
1311868235.179665 rgb/1311868235.179665.png 1311868235.188790 depth/1311868235.188790.png
1311868235.211489 rgb/1311868235.211489.png 1311868235.226668 depth/1311868235.226668.png
1311868235.243614 rgb/1311868235.243614.png 1311868235.256378 depth/1311868235.256378.png
1311868235.279710 rgb/1311868235.279710.png 1311868235.289189 depth/1311868235.289189.png
1311868235.311695 rgb/1311868235.311695.png 1311868235.325958 depth/1311868235.325958.png
1311868235.343699 rgb/1311868235.343699.png 1311868235.358123 depth/1311868235.358123.png
1311868235.379762 rgb/1311868235.379762.png 1311868235.390186 depth/1311868235.390186.png
1311868235.411537 rgb/1311868235.411537.png 1311868235.423937 depth/1311868235.423937.png
1311868235.443732 rgb/1311868235.443732.png 1311868235.458843 depth/1311868235.458843.png
1311868235.479571 rgb/1311868235.479571.png 1311868235.487231 depth/1311868235.487231.png
1311868235.511713 rgb/1311868235.511713.png 1311868235.526273 depth/1311868235.526273.png
1311868235.543566 rgb/1311868235.543566.png 1311868235.557763 depth/1311868235.557763.png
1311868235.579657 rgb/1311868235.579657.png 1311868235.590548 depth/1311868235.590548.png
1311868235.611793 rgb/1311868235.611793.png 1311868235.627906 depth/1311868235.627906.png
1311868235.643525 rgb/1311868235.643525.png 1311868235.656834 depth/1311868235.656834.png
1311868235.679690 rgb/1311868235.679690.png 1311868235.686960 depth/1311868235.686960.png
1311868235.711568 rgb/1311868235.711568.png 1311868235.725908 depth/1311868235.725908.png
1311868235.743898 rgb/1311868235.743898.png 1311868235.754141 depth/1311868235.754141.png
1311868235.779537 rgb/1311868235.779537.png 1311868235.788257 depth/1311868235.788257.png
1311868235.811896 rgb/1311868235.811896.png 1311868235.825362 depth/1311868235.825362.png
1311868235.843663 rgb/1311868235.843663.png 1311868235.858308 depth/1311868235.858308.png
1311868235.879619 rgb/1311868235.879619.png 1311868235.888708 depth/1311868235.888708.png
1311868235.911551 rgb/1311868235.911551.png 1311868235.921561 depth/1311868235.921561.png
1311868235.943694 rgb/1311868235.943694.png 1311868235.956001 depth/1311868235.956001.png
1311868235.979648 rgb/1311868235.979648.png 1311868235.988034 depth/1311868235.988034.png
1311868236.011678 rgb/1311868236.011678.png 1311868236.025635 depth/1311868236.025635.png
1311868236.043684 rgb/1311868236.043684.png 1311868236.060014 depth/1311868236.060014.png
1311868236.079629 rgb/1311868236.079629.png 1311868236.088707 depth/1311868236.088707.png
1311868236.111800 rgb/1311868236.111800.png 1311868236.126979 depth/1311868236.126979.png
1311868236.143661 rgb/1311868236.143661.png 1311868236.161045 depth/1311868236.161045.png
1311868236.179561 rgb/1311868236.179561.png 1311868236.189928 depth/1311868236.189928.png
1311868236.211655 rgb/1311868236.211655.png 1311868236.224661 depth/1311868236.224661.png
1311868236.243642 rgb/1311868236.243642.png 1311868236.258926 depth/1311868236.258926.png
1311868236.279495 rgb/1311868236.279495.png 1311868236.287882 depth/1311868236.287882.png
1311868236.311580 rgb/1311868236.311580.png 1311868236.326498 depth/1311868236.326498.png
1311868236.343770 rgb/1311868236.343770.png 1311868236.354671 depth/1311868236.354671.png
1311868236.379539 rgb/1311868236.379539.png 1311868236.392383 depth/1311868236.392383.png
1311868236.412852 rgb/1311868236.412852.png 1311868236.424464 depth/1311868236.424464.png
1311868236.443514 rgb/1311868236.443514.png 1311868236.456467 depth/1311868236.456467.png
1311868236.479602 rgb/1311868236.479602.png 1311868236.492818 depth/1311868236.492818.png
1311868236.511583 rgb/1311868236.511583.png 1311868236.524614 depth/1311868236.524614.png
1311868236.543672 rgb/1311868236.543672.png 1311868236.559314 depth/1311868236.559314.png
1311868236.579656 rgb/1311868236.579656.png 1311868236.590405 depth/1311868236.590405.png
1311868236.611596 rgb/1311868236.611596.png 1311868236.624908 depth/1311868236.624908.png
1311868236.647654 rgb/1311868236.647654.png 1311868236.657752 depth/1311868236.657752.png
1311868236.679569 rgb/1311868236.679569.png 1311868236.690922 depth/1311868236.690922.png
1311868236.711710 rgb/1311868236.711710.png 1311868236.725385 depth/1311868236.725385.png
1311868236.747574 rgb/1311868236.747574.png 1311868236.757142 depth/1311868236.757142.png
1311868236.779605 rgb/1311868236.779605.png 1311868236.791103 depth/1311868236.791103.png
1311868236.811656 rgb/1311868236.811656.png 1311868236.828096 depth/1311868236.828096.png
1311868236.847644 rgb/1311868236.847644.png 1311868236.860331 depth/1311868236.860331.png
1311868236.879498 rgb/1311868236.879498.png 1311868236.892124 depth/1311868236.892124.png
1311868236.911822 rgb/1311868236.911822.png 1311868236.926204 depth/1311868236.926204.png
1311868236.947572 rgb/1311868236.947572.png 1311868236.957016 depth/1311868236.957016.png
1311868236.979635 rgb/1311868236.979635.png 1311868236.996099 depth/1311868236.996099.png
1311868237.011585 rgb/1311868237.011585.png 1311868237.026224 depth/1311868237.026224.png
1311868237.047783 rgb/1311868237.047783.png 1311868237.056067 depth/1311868237.056067.png
1311868237.079739 rgb/1311868237.079739.png 1311868237.098161 depth/1311868237.098161.png
1311868237.111617 rgb/1311868237.111617.png 1311868237.122381 depth/1311868237.122381.png
1311868237.147698 rgb/1311868237.147698.png 1311868237.156983 depth/1311868237.156983.png
1311868237.179506 rgb/1311868237.179506.png 1311868237.190662 depth/1311868237.190662.png
1311868237.211747 rgb/1311868237.211747.png 1311868237.226916 depth/1311868237.226916.png
1311868237.247704 rgb/1311868237.247704.png 1311868237.258394 depth/1311868237.258394.png
1311868237.279719 rgb/1311868237.279719.png 1311868237.295102 depth/1311868237.295102.png
1311868237.311685 rgb/1311868237.311685.png 1311868237.327288 depth/1311868237.327288.png
1311868237.347705 rgb/1311868237.347705.png 1311868237.359320 depth/1311868237.359320.png
1311868237.379984 rgb/1311868237.379984.png 1311868237.390722 depth/1311868237.390722.png
1311868237.411750 rgb/1311868237.411750.png 1311868237.424941 depth/1311868237.424941.png
1311868237.447678 rgb/1311868237.447678.png 1311868237.456755 depth/1311868237.456755.png
1311868237.479718 rgb/1311868237.479718.png 1311868237.492241 depth/1311868237.492241.png
1311868237.511663 rgb/1311868237.511663.png 1311868237.526821 depth/1311868237.526821.png
1311868237.547675 rgb/1311868237.547675.png 1311868237.557656 depth/1311868237.557656.png
1311868237.579714 rgb/1311868237.579714.png 1311868237.594326 depth/1311868237.594326.png
1311868237.611575 rgb/1311868237.611575.png 1311868237.623046 depth/1311868237.623046.png
1311868237.647688 rgb/1311868237.647688.png 1311868237.659855 depth/1311868237.659855.png
1311868237.679616 rgb/1311868237.679616.png 1311868237.693300 depth/1311868237.693300.png
1311868237.711933 rgb/1311868237.711933.png 1311868237.726827 depth/1311868237.726827.png
1311868237.747723 rgb/1311868237.747723.png 1311868237.763258 depth/1311868237.763258.png
1311868237.779615 rgb/1311868237.779615.png 1311868237.791001 depth/1311868237.791001.png
1311868237.811811 rgb/1311868237.811811.png 1311868237.826566 depth/1311868237.826566.png
1311868237.847748 rgb/1311868237.847748.png 1311868237.862605 depth/1311868237.862605.png
1311868237.879660 rgb/1311868237.879660.png 1311868237.891412 depth/1311868237.891412.png
1311868237.911846 rgb/1311868237.911846.png 1311868237.926276 depth/1311868237.926276.png
1311868237.947730 rgb/1311868237.947730.png 1311868237.961661 depth/1311868237.961661.png
1311868237.979641 rgb/1311868237.979641.png 1311868237.994909 depth/1311868237.994909.png
1311868238.011682 rgb/1311868238.011682.png 1311868238.021950 depth/1311868238.021950.png
1311868238.047724 rgb/1311868238.047724.png 1311868238.060620 depth/1311868238.060620.png
1311868238.079831 rgb/1311868238.079831.png 1311868238.093002 depth/1311868238.093002.png
1311868238.111670 rgb/1311868238.111670.png 1311868238.123324 depth/1311868238.123324.png
1311868238.147711 rgb/1311868238.147711.png 1311868238.160289 depth/1311868238.160289.png
1311868238.179768 rgb/1311868238.179768.png 1311868238.192548 depth/1311868238.192548.png
1311868238.211730 rgb/1311868238.211730.png 1311868238.224936 depth/1311868238.224936.png
1311868238.247769 rgb/1311868238.247769.png 1311868238.262497 depth/1311868238.262497.png
1311868238.279669 rgb/1311868238.279669.png 1311868238.291972 depth/1311868238.291972.png
1311868238.311749 rgb/1311868238.311749.png 1311868238.325272 depth/1311868238.325272.png
1311868238.347701 rgb/1311868238.347701.png 1311868238.363991 depth/1311868238.363991.png
1311868238.379617 rgb/1311868238.379617.png 1311868238.389787 depth/1311868238.389787.png
1311868238.411808 rgb/1311868238.411808.png 1311868238.425382 depth/1311868238.425382.png
1311868238.447579 rgb/1311868238.447579.png 1311868238.459693 depth/1311868238.459693.png
1311868238.479644 rgb/1311868238.479644.png 1311868238.491772 depth/1311868238.491772.png
1311868238.511638 rgb/1311868238.511638.png 1311868238.521638 depth/1311868238.521638.png
1311868238.547647 rgb/1311868238.547647.png 1311868238.560011 depth/1311868238.560011.png
1311868238.579703 rgb/1311868238.579703.png 1311868238.590363 depth/1311868238.590363.png
1311868238.611939 rgb/1311868238.611939.png 1311868238.623375 depth/1311868238.623375.png
1311868238.647718 rgb/1311868238.647718.png 1311868238.659595 depth/1311868238.659595.png
1311868238.679756 rgb/1311868238.679756.png 1311868238.691258 depth/1311868238.691258.png
1311868238.711811 rgb/1311868238.711811.png 1311868238.725761 depth/1311868238.725761.png
1311868238.747681 rgb/1311868238.747681.png 1311868238.758028 depth/1311868238.758028.png
1311868238.779734 rgb/1311868238.779734.png 1311868238.792777 depth/1311868238.792777.png
1311868238.811727 rgb/1311868238.811727.png 1311868238.822174 depth/1311868238.822174.png
1311868238.847715 rgb/1311868238.847715.png 1311868238.861426 depth/1311868238.861426.png
1311868238.879655 rgb/1311868238.879655.png 1311868238.891057 depth/1311868238.891057.png
1311868238.911768 rgb/1311868238.911768.png 1311868238.923426 depth/1311868238.923426.png
1311868238.947727 rgb/1311868238.947727.png 1311868238.960206 depth/1311868238.960206.png
1311868238.979698 rgb/1311868238.979698.png 1311868238.991958 depth/1311868238.991958.png
1311868239.011813 rgb/1311868239.011813.png 1311868239.026818 depth/1311868239.026818.png
1311868239.047859 rgb/1311868239.047859.png 1311868239.058701 depth/1311868239.058701.png
1311868239.079767 rgb/1311868239.079767.png 1311868239.091227 depth/1311868239.091227.png
1311868239.111923 rgb/1311868239.111923.png 1311868239.125133 depth/1311868239.125133.png
1311868239.147701 rgb/1311868239.147701.png 1311868239.161796 depth/1311868239.161796.png
1311868239.179952 rgb/1311868239.179952.png 1311868239.191238 depth/1311868239.191238.png
1311868239.211956 rgb/1311868239.211956.png 1311868239.227023 depth/1311868239.227023.png
1311868239.247740 rgb/1311868239.247740.png 1311868239.260889 depth/1311868239.260889.png
1311868239.279647 rgb/1311868239.279647.png 1311868239.289618 depth/1311868239.289618.png
1311868239.311701 rgb/1311868239.311701.png 1311868239.325948 depth/1311868239.325948.png
1311868239.347666 rgb/1311868239.347666.png 1311868239.359050 depth/1311868239.359050.png
1311868239.379722 rgb/1311868239.379722.png 1311868239.389867 depth/1311868239.389867.png
1311868239.411681 rgb/1311868239.411681.png 1311868239.425044 depth/1311868239.425044.png
1311868239.447769 rgb/1311868239.447769.png 1311868239.458929 depth/1311868239.458929.png
1311868239.479757 rgb/1311868239.479757.png 1311868239.490755 depth/1311868239.490755.png
1311868239.511807 rgb/1311868239.511807.png 1311868239.529646 depth/1311868239.529646.png
1311868239.547793 rgb/1311868239.547793.png 1311868239.558282 depth/1311868239.558282.png
1311868239.579832 rgb/1311868239.579832.png 1311868239.591313 depth/1311868239.591313.png
1311868239.611936 rgb/1311868239.611936.png 1311868239.625302 depth/1311868239.625302.png
1311868239.647799 rgb/1311868239.647799.png 1311868239.660758 depth/1311868239.660758.png
1311868239.679838 rgb/1311868239.679838.png 1311868239.689895 depth/1311868239.689895.png
1311868239.711814 rgb/1311868239.711814.png 1311868239.727318 depth/1311868239.727318.png
1311868239.747890 rgb/1311868239.747890.png 1311868239.760894 depth/1311868239.760894.png
1311868239.779802 rgb/1311868239.779802.png 1311868239.793392 depth/1311868239.793392.png
1311868239.811866 rgb/1311868239.811866.png 1311868239.826228 depth/1311868239.826228.png
1311868239.847692 rgb/1311868239.847692.png 1311868239.859950 depth/1311868239.859950.png
1311868239.879821 rgb/1311868239.879821.png 1311868239.892565 depth/1311868239.892565.png
1311868239.912048 rgb/1311868239.912048.png 1311868239.927517 depth/1311868239.927517.png
1311868239.947914 rgb/1311868239.947914.png 1311868239.961332 depth/1311868239.961332.png
1311868239.979870 rgb/1311868239.979870.png 1311868239.992583 depth/1311868239.992583.png
1311868240.012203 rgb/1311868240.012203.png 1311868240.030627 depth/1311868240.030627.png
1311868240.047963 rgb/1311868240.047963.png 1311868240.060019 depth/1311868240.060019.png
1311868240.079916 rgb/1311868240.079916.png 1311868240.092708 depth/1311868240.092708.png
1311868240.111831 rgb/1311868240.111831.png 1311868240.125948 depth/1311868240.125948.png
1311868240.147812 rgb/1311868240.147812.png 1311868240.159774 depth/1311868240.159774.png
1311868240.180037 rgb/1311868240.180037.png 1311868240.194947 depth/1311868240.194947.png
1311868240.211870 rgb/1311868240.211870.png 1311868240.228459 depth/1311868240.228459.png
1311868240.247823 rgb/1311868240.247823.png 1311868240.258951 depth/1311868240.258951.png
1311868240.279833 rgb/1311868240.279833.png 1311868240.293365 depth/1311868240.293365.png
1311868240.311899 rgb/1311868240.311899.png 1311868240.325864 depth/1311868240.325864.png
1311868240.347732 rgb/1311868240.347732.png 1311868240.357706 depth/1311868240.357706.png
1311868240.379758 rgb/1311868240.379758.png 1311868240.394263 depth/1311868240.394263.png
1311868240.412142 rgb/1311868240.412142.png 1311868240.427587 depth/1311868240.427587.png
1311868240.447900 rgb/1311868240.447900.png 1311868240.460674 depth/1311868240.460674.png
1311868240.480028 rgb/1311868240.480028.png 1311868240.496243 depth/1311868240.496243.png
1311868240.512225 rgb/1311868240.512225.png 1311868240.525348 depth/1311868240.525348.png
1311868240.547745 rgb/1311868240.547745.png 1311868240.559654 depth/1311868240.559654.png
1311868240.579717 rgb/1311868240.579717.png 1311868240.594851 depth/1311868240.594851.png
1311868240.611779 rgb/1311868240.611779.png 1311868240.626849 depth/1311868240.626849.png
1311868240.647892 rgb/1311868240.647892.png 1311868240.659999 depth/1311868240.659999.png
1311868240.679815 rgb/1311868240.679815.png 1311868240.694244 depth/1311868240.694244.png
1311868240.711873 rgb/1311868240.711873.png 1311868240.729530 depth/1311868240.729530.png
1311868240.748004 rgb/1311868240.748004.png 1311868240.759700 depth/1311868240.759700.png
1311868240.779858 rgb/1311868240.779858.png 1311868240.793847 depth/1311868240.793847.png
1311868240.811863 rgb/1311868240.811863.png 1311868240.826433 depth/1311868240.826433.png
1311868240.879754 rgb/1311868240.879754.png 1311868240.868050 depth/1311868240.868050.png
1311868240.911960 rgb/1311868240.911960.png 1311868240.926676 depth/1311868240.926676.png
1311868240.947862 rgb/1311868240.947862.png 1311868240.958642 depth/1311868240.958642.png
1311868240.980015 rgb/1311868240.980015.png 1311868240.996545 depth/1311868240.996545.png
1311868241.011989 rgb/1311868241.011989.png 1311868241.026135 depth/1311868241.026135.png
1311868241.047933 rgb/1311868241.047933.png 1311868241.061283 depth/1311868241.061283.png
1311868241.079985 rgb/1311868241.079985.png 1311868241.094743 depth/1311868241.094743.png
1311868241.111816 rgb/1311868241.111816.png 1311868241.126527 depth/1311868241.126527.png
1311868241.148015 rgb/1311868241.148015.png 1311868241.160868 depth/1311868241.160868.png
1311868241.179775 rgb/1311868241.179775.png 1311868241.195828 depth/1311868241.195828.png
1311868241.211864 rgb/1311868241.211864.png 1311868241.225637 depth/1311868241.225637.png
1311868241.247832 rgb/1311868241.247832.png 1311868241.260669 depth/1311868241.260669.png
1311868241.279951 rgb/1311868241.279951.png 1311868241.295619 depth/1311868241.295619.png
1311868241.311846 rgb/1311868241.311846.png 1311868241.327348 depth/1311868241.327348.png
1311868241.348159 rgb/1311868241.348159.png 1311868241.361428 depth/1311868241.361428.png
1311868241.379991 rgb/1311868241.379991.png 1311868241.394814 depth/1311868241.394814.png
1311868241.411927 rgb/1311868241.411927.png 1311868241.427858 depth/1311868241.427858.png
1311868241.447810 rgb/1311868241.447810.png 1311868241.462746 depth/1311868241.462746.png
1311868241.479924 rgb/1311868241.479924.png 1311868241.495494 depth/1311868241.495494.png
1311868241.512153 rgb/1311868241.512153.png 1311868241.528389 depth/1311868241.528389.png
1311868241.579911 rgb/1311868241.579911.png 1311868241.563938 depth/1311868241.563938.png
1311868241.611956 rgb/1311868241.611956.png 1311868241.627214 depth/1311868241.627214.png
1311868241.648036 rgb/1311868241.648036.png 1311868241.662749 depth/1311868241.662749.png
1311868241.679969 rgb/1311868241.679969.png 1311868241.694677 depth/1311868241.694677.png
1311868241.712640 rgb/1311868241.712640.png 1311868241.726612 depth/1311868241.726612.png
1311868241.747996 rgb/1311868241.747996.png 1311868241.762745 depth/1311868241.762745.png
1311868241.779865 rgb/1311868241.779865.png 1311868241.793970 depth/1311868241.793970.png
1311868241.811843 rgb/1311868241.811843.png 1311868241.825481 depth/1311868241.825481.png
1311868241.847976 rgb/1311868241.847976.png 1311868241.861957 depth/1311868241.861957.png
1311868241.879857 rgb/1311868241.879857.png 1311868241.893685 depth/1311868241.893685.png
1311868241.911969 rgb/1311868241.911969.png 1311868241.925761 depth/1311868241.925761.png
1311868241.947838 rgb/1311868241.947838.png 1311868241.962577 depth/1311868241.962577.png
1311868241.979902 rgb/1311868241.979902.png 1311868241.993950 depth/1311868241.993950.png
1311868242.011931 rgb/1311868242.011931.png 1311868242.028824 depth/1311868242.028824.png
1311868242.047949 rgb/1311868242.047949.png 1311868242.063442 depth/1311868242.063442.png
1311868242.080011 rgb/1311868242.080011.png 1311868242.096649 depth/1311868242.096649.png
1311868242.111944 rgb/1311868242.111944.png 1311868242.126174 depth/1311868242.126174.png
1311868242.147934 rgb/1311868242.147934.png 1311868242.162661 depth/1311868242.162661.png
1311868242.180028 rgb/1311868242.180028.png 1311868242.196561 depth/1311868242.196561.png
1311868242.212185 rgb/1311868242.212185.png 1311868242.226612 depth/1311868242.226612.png
1311868242.247919 rgb/1311868242.247919.png 1311868242.261886 depth/1311868242.261886.png
1311868242.279969 rgb/1311868242.279969.png 1311868242.294353 depth/1311868242.294353.png
1311868242.312146 rgb/1311868242.312146.png 1311868242.327605 depth/1311868242.327605.png
1311868242.347903 rgb/1311868242.347903.png 1311868242.362223 depth/1311868242.362223.png
1311868242.379943 rgb/1311868242.379943.png 1311868242.394235 depth/1311868242.394235.png
1311868242.412008 rgb/1311868242.412008.png 1311868242.427036 depth/1311868242.427036.png
1311868242.447942 rgb/1311868242.447942.png 1311868242.462353 depth/1311868242.462353.png
1311868242.479984 rgb/1311868242.479984.png 1311868242.493946 depth/1311868242.493946.png
1311868242.511969 rgb/1311868242.511969.png 1311868242.526615 depth/1311868242.526615.png
1311868242.580083 rgb/1311868242.580083.png 1311868242.566495 depth/1311868242.566495.png
1311868242.612269 rgb/1311868242.612269.png 1311868242.627472 depth/1311868242.627472.png
1311868242.679930 rgb/1311868242.679930.png 1311868242.667488 depth/1311868242.667488.png
1311868242.712253 rgb/1311868242.712253.png 1311868242.694130 depth/1311868242.694130.png
1311868242.747909 rgb/1311868242.747909.png 1311868242.732996 depth/1311868242.732996.png
1311868242.779977 rgb/1311868242.779977.png 1311868242.793489 depth/1311868242.793489.png
1311868242.847992 rgb/1311868242.847992.png 1311868242.863742 depth/1311868242.863742.png
1311868242.879888 rgb/1311868242.879888.png 1311868242.893625 depth/1311868242.893625.png
1311868242.912047 rgb/1311868242.912047.png 1311868242.931911 depth/1311868242.931911.png
1311868242.948092 rgb/1311868242.948092.png 1311868242.962237 depth/1311868242.962237.png
1311868243.012214 rgb/1311868243.012214.png 1311868242.999440 depth/1311868242.999440.png
1311868243.048093 rgb/1311868243.048093.png 1311868243.030267 depth/1311868243.030267.png
1311868243.079963 rgb/1311868243.079963.png 1311868243.065614 depth/1311868243.065614.png
1311868243.111904 rgb/1311868243.111904.png 1311868243.094622 depth/1311868243.094622.png
1311868243.148081 rgb/1311868243.148081.png 1311868243.131233 depth/1311868243.131233.png
1311868243.180098 rgb/1311868243.180098.png 1311868243.165261 depth/1311868243.165261.png
1311868243.211968 rgb/1311868243.211968.png 1311868243.195099 depth/1311868243.195099.png
1311868243.248114 rgb/1311868243.248114.png 1311868243.232137 depth/1311868243.232137.png
1311868243.280037 rgb/1311868243.280037.png 1311868243.267009 depth/1311868243.267009.png
1311868243.312010 rgb/1311868243.312010.png 1311868243.299211 depth/1311868243.299211.png
1311868243.348087 rgb/1311868243.348087.png 1311868243.363556 depth/1311868243.363556.png
1311868243.411942 rgb/1311868243.411942.png 1311868243.398679 depth/1311868243.398679.png
1311868243.448204 rgb/1311868243.448204.png 1311868243.433005 depth/1311868243.433005.png
1311868243.480135 rgb/1311868243.480135.png 1311868243.495035 depth/1311868243.495035.png
1311868243.548097 rgb/1311868243.548097.png 1311868243.532500 depth/1311868243.532500.png
1311868243.580031 rgb/1311868243.580031.png 1311868243.567513 depth/1311868243.567513.png
1311868243.611954 rgb/1311868243.611954.png 1311868243.593573 depth/1311868243.593573.png
1311868243.648052 rgb/1311868243.648052.png 1311868243.632824 depth/1311868243.632824.png
1311868243.680036 rgb/1311868243.680036.png 1311868243.668349 depth/1311868243.668349.png
1311868243.712048 rgb/1311868243.712048.png 1311868243.696565 depth/1311868243.696565.png
1311868243.747912 rgb/1311868243.747912.png 1311868243.732961 depth/1311868243.732961.png
1311868243.779970 rgb/1311868243.779970.png 1311868243.766757 depth/1311868243.766757.png
1311868243.811933 rgb/1311868243.811933.png 1311868243.795568 depth/1311868243.795568.png
1311868243.848171 rgb/1311868243.848171.png 1311868243.829790 depth/1311868243.829790.png
1311868243.880069 rgb/1311868243.880069.png 1311868243.866513 depth/1311868243.866513.png
1311868243.912060 rgb/1311868243.912060.png 1311868243.901901 depth/1311868243.901901.png
1311868243.948200 rgb/1311868243.948200.png 1311868243.929651 depth/1311868243.929651.png
1311868243.979984 rgb/1311868243.979984.png 1311868243.966068 depth/1311868243.966068.png
1311868244.012101 rgb/1311868244.012101.png 1311868243.997409 depth/1311868243.997409.png
1311868244.048067 rgb/1311868244.048067.png 1311868244.030514 depth/1311868244.030514.png
1311868244.080141 rgb/1311868244.080141.png 1311868244.066062 depth/1311868244.066062.png
1311868244.112211 rgb/1311868244.112211.png 1311868244.098434 depth/1311868244.098434.png
1311868244.148092 rgb/1311868244.148092.png 1311868244.162988 depth/1311868244.162988.png
1311868244.212047 rgb/1311868244.212047.png 1311868244.198839 depth/1311868244.198839.png
1311868244.248025 rgb/1311868244.248025.png 1311868244.262109 depth/1311868244.262109.png
1311868244.312192 rgb/1311868244.312192.png 1311868244.297550 depth/1311868244.297550.png
1311868244.348251 rgb/1311868244.348251.png 1311868244.330150 depth/1311868244.330150.png
1311868244.380022 rgb/1311868244.380022.png 1311868244.365236 depth/1311868244.365236.png
1311868244.412124 rgb/1311868244.412124.png 1311868244.398588 depth/1311868244.398588.png
1311868244.448220 rgb/1311868244.448220.png 1311868244.430616 depth/1311868244.430616.png
1311868244.480101 rgb/1311868244.480101.png 1311868244.465583 depth/1311868244.465583.png
1311868244.512251 rgb/1311868244.512251.png 1311868244.497460 depth/1311868244.497460.png
1311868244.548269 rgb/1311868244.548269.png 1311868244.530488 depth/1311868244.530488.png
1311868244.580149 rgb/1311868244.580149.png 1311868244.566405 depth/1311868244.566405.png
1311868244.612250 rgb/1311868244.612250.png 1311868244.598720 depth/1311868244.598720.png
1311868244.648157 rgb/1311868244.648157.png 1311868244.663355 depth/1311868244.663355.png
1311868244.712115 rgb/1311868244.712115.png 1311868244.701010 depth/1311868244.701010.png
1311868244.748285 rgb/1311868244.748285.png 1311868244.734571 depth/1311868244.734571.png
1311868244.780046 rgb/1311868244.780046.png 1311868244.767062 depth/1311868244.767062.png
1311868244.812104 rgb/1311868244.812104.png 1311868244.797579 depth/1311868244.797579.png
1311868244.848096 rgb/1311868244.848096.png 1311868244.833981 depth/1311868244.833981.png
1311868244.880436 rgb/1311868244.880436.png 1311868244.863194 depth/1311868244.863194.png
1311868244.912189 rgb/1311868244.912189.png 1311868244.899663 depth/1311868244.899663.png
1311868244.948056 rgb/1311868244.948056.png 1311868244.930652 depth/1311868244.930652.png
1311868244.980073 rgb/1311868244.980073.png 1311868244.966161 depth/1311868244.966161.png
1311868245.012295 rgb/1311868245.012295.png 1311868244.997817 depth/1311868244.997817.png
1311868245.048320 rgb/1311868245.048320.png 1311868245.030713 depth/1311868245.030713.png
1311868245.080152 rgb/1311868245.080152.png 1311868245.068230 depth/1311868245.068230.png
1311868245.112252 rgb/1311868245.112252.png 1311868245.100094 depth/1311868245.100094.png
1311868245.148152 rgb/1311868245.148152.png 1311868245.132550 depth/1311868245.132550.png
1311868245.179920 rgb/1311868245.179920.png 1311868245.168625 depth/1311868245.168625.png
1311868245.212180 rgb/1311868245.212180.png 1311868245.198748 depth/1311868245.198748.png
1311868245.248256 rgb/1311868245.248256.png 1311868245.230284 depth/1311868245.230284.png
1311868245.280237 rgb/1311868245.280237.png 1311868245.268076 depth/1311868245.268076.png
1311868245.312188 rgb/1311868245.312188.png 1311868245.297794 depth/1311868245.297794.png
1311868245.348205 rgb/1311868245.348205.png 1311868245.330195 depth/1311868245.330195.png
1311868245.380074 rgb/1311868245.380074.png 1311868245.368326 depth/1311868245.368326.png
1311868245.412242 rgb/1311868245.412242.png 1311868245.397655 depth/1311868245.397655.png
1311868245.448230 rgb/1311868245.448230.png 1311868245.433333 depth/1311868245.433333.png
1311868245.480081 rgb/1311868245.480081.png 1311868245.469521 depth/1311868245.469521.png
1311868245.512280 rgb/1311868245.512280.png 1311868245.499686 depth/1311868245.499686.png
1311868245.548216 rgb/1311868245.548216.png 1311868245.532317 depth/1311868245.532317.png
1311868245.580262 rgb/1311868245.580262.png 1311868245.569225 depth/1311868245.569225.png
1311868245.612262 rgb/1311868245.612262.png 1311868245.600933 depth/1311868245.600933.png
1311868245.648241 rgb/1311868245.648241.png 1311868245.632668 depth/1311868245.632668.png
1311868245.680250 rgb/1311868245.680250.png 1311868245.669122 depth/1311868245.669122.png
1311868245.716121 rgb/1311868245.716121.png 1311868245.702053 depth/1311868245.702053.png
1311868245.748208 rgb/1311868245.748208.png 1311868245.733429 depth/1311868245.733429.png
1311868245.780177 rgb/1311868245.780177.png 1311868245.769680 depth/1311868245.769680.png
1311868245.816257 rgb/1311868245.816257.png 1311868245.799797 depth/1311868245.799797.png
1311868245.848193 rgb/1311868245.848193.png 1311868245.835753 depth/1311868245.835753.png
1311868245.880182 rgb/1311868245.880182.png 1311868245.869256 depth/1311868245.869256.png
1311868245.916227 rgb/1311868245.916227.png 1311868245.898307 depth/1311868245.898307.png
1311868245.948179 rgb/1311868245.948179.png 1311868245.935377 depth/1311868245.935377.png
1311868245.980265 rgb/1311868245.980265.png 1311868245.965600 depth/1311868245.965600.png
1311868246.016098 rgb/1311868246.016098.png 1311868246.000465 depth/1311868246.000465.png
1311868246.048196 rgb/1311868246.048196.png 1311868246.032994 depth/1311868246.032994.png
1311868246.080289 rgb/1311868246.080289.png 1311868246.069608 depth/1311868246.069608.png
1311868246.116229 rgb/1311868246.116229.png 1311868246.098082 depth/1311868246.098082.png
1311868246.148198 rgb/1311868246.148198.png 1311868246.134697 depth/1311868246.134697.png
1311868246.180201 rgb/1311868246.180201.png 1311868246.168861 depth/1311868246.168861.png
1311868246.216086 rgb/1311868246.216086.png 1311868246.201654 depth/1311868246.201654.png
1311868246.248127 rgb/1311868246.248127.png 1311868246.232147 depth/1311868246.232147.png
1311868246.280157 rgb/1311868246.280157.png 1311868246.267610 depth/1311868246.267610.png
1311868246.316184 rgb/1311868246.316184.png 1311868246.299361 depth/1311868246.299361.png
1311868246.348101 rgb/1311868246.348101.png 1311868246.332354 depth/1311868246.332354.png
1311868246.380220 rgb/1311868246.380220.png 1311868246.369599 depth/1311868246.369599.png
1311868246.416139 rgb/1311868246.416139.png 1311868246.400571 depth/1311868246.400571.png
1311868246.448298 rgb/1311868246.448298.png 1311868246.437181 depth/1311868246.437181.png
1311868246.480362 rgb/1311868246.480362.png 1311868246.466561 depth/1311868246.466561.png
1311868246.516170 rgb/1311868246.516170.png 1311868246.500549 depth/1311868246.500549.png
1311868246.548357 rgb/1311868246.548357.png 1311868246.537414 depth/1311868246.537414.png
1311868246.580161 rgb/1311868246.580161.png 1311868246.567438 depth/1311868246.567438.png
1311868246.616068 rgb/1311868246.616068.png 1311868246.598763 depth/1311868246.598763.png
1311868246.648250 rgb/1311868246.648250.png 1311868246.634586 depth/1311868246.634586.png
1311868246.680335 rgb/1311868246.680335.png 1311868246.666996 depth/1311868246.666996.png
1311868246.716264 rgb/1311868246.716264.png 1311868246.700669 depth/1311868246.700669.png
1311868246.748855 rgb/1311868246.748855.png 1311868246.737587 depth/1311868246.737587.png
1311868246.780364 rgb/1311868246.780364.png 1311868246.769254 depth/1311868246.769254.png
1311868246.816180 rgb/1311868246.816180.png 1311868246.798114 depth/1311868246.798114.png
1311868246.848370 rgb/1311868246.848370.png 1311868246.837574 depth/1311868246.837574.png
1311868246.880261 rgb/1311868246.880261.png 1311868246.869140 depth/1311868246.869140.png
1311868246.916243 rgb/1311868246.916243.png 1311868246.899105 depth/1311868246.899105.png
1311868246.948199 rgb/1311868246.948199.png 1311868246.939224 depth/1311868246.939224.png
1311868246.980258 rgb/1311868246.980258.png 1311868246.965703 depth/1311868246.965703.png
1311868247.016214 rgb/1311868247.016214.png 1311868246.997807 depth/1311868246.997807.png
1311868247.048425 rgb/1311868247.048425.png 1311868247.038653 depth/1311868247.038653.png
1311868247.080182 rgb/1311868247.080182.png 1311868247.066828 depth/1311868247.066828.png
1311868247.116311 rgb/1311868247.116311.png 1311868247.099315 depth/1311868247.099315.png
1311868247.148430 rgb/1311868247.148430.png 1311868247.137293 depth/1311868247.137293.png
1311868247.180293 rgb/1311868247.180293.png 1311868247.168256 depth/1311868247.168256.png
1311868247.216432 rgb/1311868247.216432.png 1311868247.199154 depth/1311868247.199154.png
1311868247.248170 rgb/1311868247.248170.png 1311868247.234191 depth/1311868247.234191.png
1311868247.280345 rgb/1311868247.280345.png 1311868247.268034 depth/1311868247.268034.png
1311868247.316293 rgb/1311868247.316293.png 1311868247.301142 depth/1311868247.301142.png
1311868247.348285 rgb/1311868247.348285.png 1311868247.334618 depth/1311868247.334618.png
1311868247.380602 rgb/1311868247.380602.png 1311868247.368875 depth/1311868247.368875.png
1311868247.416268 rgb/1311868247.416268.png 1311868247.398608 depth/1311868247.398608.png
1311868247.448333 rgb/1311868247.448333.png 1311868247.437852 depth/1311868247.437852.png
1311868247.480433 rgb/1311868247.480433.png 1311868247.469227 depth/1311868247.469227.png
1311868247.516146 rgb/1311868247.516146.png 1311868247.499036 depth/1311868247.499036.png
1311868247.548460 rgb/1311868247.548460.png 1311868247.537336 depth/1311868247.537336.png
1311868247.580231 rgb/1311868247.580231.png 1311868247.570321 depth/1311868247.570321.png
1311868247.616424 rgb/1311868247.616424.png 1311868247.605218 depth/1311868247.605218.png
1311868247.648229 rgb/1311868247.648229.png 1311868247.637508 depth/1311868247.637508.png
1311868247.680389 rgb/1311868247.680389.png 1311868247.665759 depth/1311868247.665759.png
1311868247.716208 rgb/1311868247.716208.png 1311868247.703260 depth/1311868247.703260.png
1311868247.748343 rgb/1311868247.748343.png 1311868247.737791 depth/1311868247.737791.png
1311868247.780427 rgb/1311868247.780427.png 1311868247.769288 depth/1311868247.769288.png
1311868247.816205 rgb/1311868247.816205.png 1311868247.803052 depth/1311868247.803052.png
1311868247.848368 rgb/1311868247.848368.png 1311868247.837312 depth/1311868247.837312.png
1311868247.880235 rgb/1311868247.880235.png 1311868247.865912 depth/1311868247.865912.png
1311868247.916219 rgb/1311868247.916219.png 1311868247.902738 depth/1311868247.902738.png
1311868247.948167 rgb/1311868247.948167.png 1311868247.933774 depth/1311868247.933774.png
1311868247.980227 rgb/1311868247.980227.png 1311868247.965890 depth/1311868247.965890.png
1311868248.016215 rgb/1311868248.016215.png 1311868248.002931 depth/1311868248.002931.png
1311868248.048245 rgb/1311868248.048245.png 1311868248.034882 depth/1311868248.034882.png
1311868248.080326 rgb/1311868248.080326.png 1311868248.065902 depth/1311868248.065902.png
1311868248.116239 rgb/1311868248.116239.png 1311868248.102546 depth/1311868248.102546.png
1311868248.148302 rgb/1311868248.148302.png 1311868248.135080 depth/1311868248.135080.png
1311868248.180377 rgb/1311868248.180377.png 1311868248.166295 depth/1311868248.166295.png
1311868248.216356 rgb/1311868248.216356.png 1311868248.201776 depth/1311868248.201776.png
1311868248.248345 rgb/1311868248.248345.png 1311868248.239703 depth/1311868248.239703.png
1311868248.280257 rgb/1311868248.280257.png 1311868248.265695 depth/1311868248.265695.png
1311868248.316226 rgb/1311868248.316226.png 1311868248.301724 depth/1311868248.301724.png
1311868248.348315 rgb/1311868248.348315.png 1311868248.335023 depth/1311868248.335023.png
1311868248.380451 rgb/1311868248.380451.png 1311868248.367024 depth/1311868248.367024.png
1311868248.416340 rgb/1311868248.416340.png 1311868248.401736 depth/1311868248.401736.png
1311868248.448353 rgb/1311868248.448353.png 1311868248.434097 depth/1311868248.434097.png
1311868248.480364 rgb/1311868248.480364.png 1311868248.467522 depth/1311868248.467522.png
1311868248.516261 rgb/1311868248.516261.png 1311868248.503344 depth/1311868248.503344.png
1311868248.548298 rgb/1311868248.548298.png 1311868248.536471 depth/1311868248.536471.png
1311868248.580330 rgb/1311868248.580330.png 1311868248.566838 depth/1311868248.566838.png
1311868248.616364 rgb/1311868248.616364.png 1311868248.602761 depth/1311868248.602761.png
1311868248.648465 rgb/1311868248.648465.png 1311868248.634678 depth/1311868248.634678.png
1311868248.680356 rgb/1311868248.680356.png 1311868248.667205 depth/1311868248.667205.png
1311868248.716495 rgb/1311868248.716495.png 1311868248.702846 depth/1311868248.702846.png
1311868248.748482 rgb/1311868248.748482.png 1311868248.734052 depth/1311868248.734052.png
1311868248.780288 rgb/1311868248.780288.png 1311868248.766346 depth/1311868248.766346.png
1311868248.816469 rgb/1311868248.816469.png 1311868248.802354 depth/1311868248.802354.png
1311868248.848299 rgb/1311868248.848299.png 1311868248.837692 depth/1311868248.837692.png
1311868248.880380 rgb/1311868248.880380.png 1311868248.870600 depth/1311868248.870600.png
1311868248.916530 rgb/1311868248.916530.png 1311868248.907596 depth/1311868248.907596.png
1311868248.948257 rgb/1311868248.948257.png 1311868248.935123 depth/1311868248.935123.png
1311868248.980371 rgb/1311868248.980371.png 1311868248.972389 depth/1311868248.972389.png
1311868249.016517 rgb/1311868249.016517.png 1311868249.003866 depth/1311868249.003866.png
1311868249.048258 rgb/1311868249.048258.png 1311868249.033950 depth/1311868249.033950.png
1311868249.080657 rgb/1311868249.080657.png 1311868249.071928 depth/1311868249.071928.png
1311868249.116343 rgb/1311868249.116343.png 1311868249.102655 depth/1311868249.102655.png
1311868249.148549 rgb/1311868249.148549.png 1311868249.137507 depth/1311868249.137507.png
1311868249.180476 rgb/1311868249.180476.png 1311868249.169827 depth/1311868249.169827.png
1311868249.216410 rgb/1311868249.216410.png 1311868249.205621 depth/1311868249.205621.png
1311868249.248249 rgb/1311868249.248249.png 1311868249.234582 depth/1311868249.234582.png
1311868249.280715 rgb/1311868249.280715.png 1311868249.270200 depth/1311868249.270200.png
1311868249.316586 rgb/1311868249.316586.png 1311868249.302950 depth/1311868249.302950.png
1311868249.348357 rgb/1311868249.348357.png 1311868249.334354 depth/1311868249.334354.png
1311868249.380649 rgb/1311868249.380649.png 1311868249.369867 depth/1311868249.369867.png
1311868249.416459 rgb/1311868249.416459.png 1311868249.401709 depth/1311868249.401709.png
1311868249.448316 rgb/1311868249.448316.png 1311868249.435326 depth/1311868249.435326.png
1311868249.480373 rgb/1311868249.480373.png 1311868249.471210 depth/1311868249.471210.png
1311868249.516272 rgb/1311868249.516272.png 1311868249.503250 depth/1311868249.503250.png
1311868249.548294 rgb/1311868249.548294.png 1311868249.535792 depth/1311868249.535792.png
1311868249.580331 rgb/1311868249.580331.png 1311868249.569940 depth/1311868249.569940.png
1311868249.616312 rgb/1311868249.616312.png 1311868249.603120 depth/1311868249.603120.png
1311868249.648364 rgb/1311868249.648364.png 1311868249.633985 depth/1311868249.633985.png
1311868249.680685 rgb/1311868249.680685.png 1311868249.669894 depth/1311868249.669894.png
1311868249.716340 rgb/1311868249.716340.png 1311868249.701887 depth/1311868249.701887.png
1311868249.748334 rgb/1311868249.748334.png 1311868249.733888 depth/1311868249.733888.png
1311868249.780683 rgb/1311868249.780683.png 1311868249.770990 depth/1311868249.770990.png
1311868249.816620 rgb/1311868249.816620.png 1311868249.805210 depth/1311868249.805210.png
1311868249.848322 rgb/1311868249.848322.png 1311868249.834454 depth/1311868249.834454.png
1311868249.880507 rgb/1311868249.880507.png 1311868249.869851 depth/1311868249.869851.png
1311868249.916563 rgb/1311868249.916563.png 1311868249.901831 depth/1311868249.901831.png
1311868249.948306 rgb/1311868249.948306.png 1311868249.935668 depth/1311868249.935668.png
1311868249.980348 rgb/1311868249.980348.png 1311868249.971837 depth/1311868249.971837.png
1311868250.016358 rgb/1311868250.016358.png 1311868250.002150 depth/1311868250.002150.png
1311868250.048559 rgb/1311868250.048559.png 1311868250.034645 depth/1311868250.034645.png
1311868250.080466 rgb/1311868250.080466.png 1311868250.071665 depth/1311868250.071665.png
1311868250.116495 rgb/1311868250.116495.png 1311868250.103399 depth/1311868250.103399.png
1311868250.148589 rgb/1311868250.148589.png 1311868250.142995 depth/1311868250.142995.png
1311868250.180457 rgb/1311868250.180457.png 1311868250.171268 depth/1311868250.171268.png
1311868250.216361 rgb/1311868250.216361.png 1311868250.202986 depth/1311868250.202986.png
1311868250.248624 rgb/1311868250.248624.png 1311868250.241329 depth/1311868250.241329.png
1311868250.280374 rgb/1311868250.280374.png 1311868250.270874 depth/1311868250.270874.png
1311868250.316452 rgb/1311868250.316452.png 1311868250.306018 depth/1311868250.306018.png
1311868250.348963 rgb/1311868250.348963.png 1311868250.340082 depth/1311868250.340082.png
1311868250.380598 rgb/1311868250.380598.png 1311868250.370257 depth/1311868250.370257.png
1311868250.416431 rgb/1311868250.416431.png 1311868250.403761 depth/1311868250.403761.png
1311868250.448319 rgb/1311868250.448319.png 1311868250.438294 depth/1311868250.438294.png
1311868250.480450 rgb/1311868250.480450.png 1311868250.469889 depth/1311868250.469889.png
1311868250.516364 rgb/1311868250.516364.png 1311868250.502216 depth/1311868250.502216.png
1311868250.548715 rgb/1311868250.548715.png 1311868250.538123 depth/1311868250.538123.png
1311868250.580440 rgb/1311868250.580440.png 1311868250.571480 depth/1311868250.571480.png
1311868250.616408 rgb/1311868250.616408.png 1311868250.602134 depth/1311868250.602134.png
1311868250.648757 rgb/1311868250.648757.png 1311868250.637824 depth/1311868250.637824.png
1311868250.680503 rgb/1311868250.680503.png 1311868250.672483 depth/1311868250.672483.png
1311868250.716511 rgb/1311868250.716511.png 1311868250.703217 depth/1311868250.703217.png
1311868250.748430 rgb/1311868250.748430.png 1311868250.740204 depth/1311868250.740204.png
1311868250.780601 rgb/1311868250.780601.png 1311868250.770588 depth/1311868250.770588.png
1311868250.816420 rgb/1311868250.816420.png 1311868250.802296 depth/1311868250.802296.png
1311868250.848395 rgb/1311868250.848395.png 1311868250.838519 depth/1311868250.838519.png
1311868250.880463 rgb/1311868250.880463.png 1311868250.871167 depth/1311868250.871167.png
1311868250.916361 rgb/1311868250.916361.png 1311868250.902364 depth/1311868250.902364.png
1311868250.948745 rgb/1311868250.948745.png 1311868250.938035 depth/1311868250.938035.png
1311868250.980502 rgb/1311868250.980502.png 1311868250.970114 depth/1311868250.970114.png
1311868251.016390 rgb/1311868251.016390.png 1311868251.004302 depth/1311868251.004302.png
1311868251.048640 rgb/1311868251.048640.png 1311868251.039099 depth/1311868251.039099.png
1311868251.080543 rgb/1311868251.080543.png 1311868251.070062 depth/1311868251.070062.png
1311868251.116502 rgb/1311868251.116502.png 1311868251.102836 depth/1311868251.102836.png
1311868251.148411 rgb/1311868251.148411.png 1311868251.138815 depth/1311868251.138815.png
1311868251.180611 rgb/1311868251.180611.png 1311868251.171110 depth/1311868251.171110.png
1311868251.216444 rgb/1311868251.216444.png 1311868251.201988 depth/1311868251.201988.png
1311868251.248388 rgb/1311868251.248388.png 1311868251.238021 depth/1311868251.238021.png
1311868251.280411 rgb/1311868251.280411.png 1311868251.269877 depth/1311868251.269877.png
1311868251.316903 rgb/1311868251.316903.png 1311868251.307441 depth/1311868251.307441.png
1311868251.348494 rgb/1311868251.348494.png 1311868251.338709 depth/1311868251.338709.png
1311868251.380800 rgb/1311868251.380800.png 1311868251.371768 depth/1311868251.371768.png
1311868251.416874 rgb/1311868251.416874.png 1311868251.409690 depth/1311868251.409690.png
1311868251.448794 rgb/1311868251.448794.png 1311868251.442505 depth/1311868251.442505.png
1311868251.480572 rgb/1311868251.480572.png 1311868251.471430 depth/1311868251.471430.png
1311868251.516467 rgb/1311868251.516467.png 1311868251.506071 depth/1311868251.506071.png
1311868251.548661 rgb/1311868251.548661.png 1311868251.541665 depth/1311868251.541665.png
1311868251.580755 rgb/1311868251.580755.png 1311868251.573860 depth/1311868251.573860.png
1311868251.616591 rgb/1311868251.616591.png 1311868251.608834 depth/1311868251.608834.png
1311868251.649011 rgb/1311868251.649011.png 1311868251.642071 depth/1311868251.642071.png
1311868251.681056 rgb/1311868251.681056.png 1311868251.672750 depth/1311868251.672750.png
1311868251.716509 rgb/1311868251.716509.png 1311868251.706095 depth/1311868251.706095.png
1311868251.748667 rgb/1311868251.748667.png 1311868251.740405 depth/1311868251.740405.png
1311868251.780606 rgb/1311868251.780606.png 1311868251.770114 depth/1311868251.770114.png
1311868251.816706 rgb/1311868251.816706.png 1311868251.808202 depth/1311868251.808202.png
1311868251.848729 rgb/1311868251.848729.png 1311868251.843159 depth/1311868251.843159.png
1311868251.881180 rgb/1311868251.881180.png 1311868251.871734 depth/1311868251.871734.png
1311868251.916574 rgb/1311868251.916574.png 1311868251.907729 depth/1311868251.907729.png
1311868251.948786 rgb/1311868251.948786.png 1311868251.941716 depth/1311868251.941716.png
1311868251.980523 rgb/1311868251.980523.png 1311868251.972312 depth/1311868251.972312.png
1311868252.016633 rgb/1311868252.016633.png 1311868252.008720 depth/1311868252.008720.png
1311868252.048722 rgb/1311868252.048722.png 1311868252.042678 depth/1311868252.042678.png
1311868252.081141 rgb/1311868252.081141.png 1311868252.073898 depth/1311868252.073898.png
1311868252.116709 rgb/1311868252.116709.png 1311868252.108550 depth/1311868252.108550.png
1311868252.148733 rgb/1311868252.148733.png 1311868252.141590 depth/1311868252.141590.png
1311868252.180550 rgb/1311868252.180550.png 1311868252.171057 depth/1311868252.171057.png
1311868252.216665 rgb/1311868252.216665.png 1311868252.209444 depth/1311868252.209444.png
1311868252.249056 rgb/1311868252.249056.png 1311868252.243429 depth/1311868252.243429.png
1311868252.280693 rgb/1311868252.280693.png 1311868252.271730 depth/1311868252.271730.png
1311868252.316579 rgb/1311868252.316579.png 1311868252.309247 depth/1311868252.309247.png
1311868252.348634 rgb/1311868252.348634.png 1311868252.339215 depth/1311868252.339215.png
1311868252.380676 rgb/1311868252.380676.png 1311868252.373399 depth/1311868252.373399.png
1311868252.416673 rgb/1311868252.416673.png 1311868252.408545 depth/1311868252.408545.png
1311868252.448807 rgb/1311868252.448807.png 1311868252.443048 depth/1311868252.443048.png
1311868252.480598 rgb/1311868252.480598.png 1311868252.471397 depth/1311868252.471397.png
1311868252.516633 rgb/1311868252.516633.png 1311868252.507776 depth/1311868252.507776.png
1311868252.550037 rgb/1311868252.550037.png 1311868252.543394 depth/1311868252.543394.png
1311868252.580747 rgb/1311868252.580747.png 1311868252.575078 depth/1311868252.575078.png
1311868252.616626 rgb/1311868252.616626.png 1311868252.606712 depth/1311868252.606712.png
1311868252.649109 rgb/1311868252.649109.png 1311868252.640952 depth/1311868252.640952.png
1311868252.680706 rgb/1311868252.680706.png 1311868252.675892 depth/1311868252.675892.png
1311868252.716568 rgb/1311868252.716568.png 1311868252.706908 depth/1311868252.706908.png
1311868252.748687 rgb/1311868252.748687.png 1311868252.740004 depth/1311868252.740004.png
1311868252.780724 rgb/1311868252.780724.png 1311868252.774814 depth/1311868252.774814.png
1311868252.816693 rgb/1311868252.816693.png 1311868252.807295 depth/1311868252.807295.png
1311868252.848740 rgb/1311868252.848740.png 1311868252.841919 depth/1311868252.841919.png
1311868252.880663 rgb/1311868252.880663.png 1311868252.877430 depth/1311868252.877430.png
1311868252.916592 rgb/1311868252.916592.png 1311868252.906062 depth/1311868252.906062.png
1311868252.948689 rgb/1311868252.948689.png 1311868252.938457 depth/1311868252.938457.png
1311868252.980733 rgb/1311868252.980733.png 1311868252.977036 depth/1311868252.977036.png
1311868253.016742 rgb/1311868253.016742.png 1311868253.009329 depth/1311868253.009329.png
1311868253.048837 rgb/1311868253.048837.png 1311868253.041027 depth/1311868253.041027.png
1311868253.080812 rgb/1311868253.080812.png 1311868253.075229 depth/1311868253.075229.png
1311868253.116735 rgb/1311868253.116735.png 1311868253.109584 depth/1311868253.109584.png
1311868253.148796 rgb/1311868253.148796.png 1311868253.139324 depth/1311868253.139324.png
1311868253.181948 rgb/1311868253.181948.png 1311868253.177590 depth/1311868253.177590.png
1311868253.216569 rgb/1311868253.216569.png 1311868253.206544 depth/1311868253.206544.png
1311868253.248725 rgb/1311868253.248725.png 1311868253.238418 depth/1311868253.238418.png
1311868253.280713 rgb/1311868253.280713.png 1311868253.276220 depth/1311868253.276220.png
1311868253.316664 rgb/1311868253.316664.png 1311868253.306046 depth/1311868253.306046.png
1311868253.348831 rgb/1311868253.348831.png 1311868253.341767 depth/1311868253.341767.png
1311868253.381067 rgb/1311868253.381067.png 1311868253.378465 depth/1311868253.378465.png
1311868253.416763 rgb/1311868253.416763.png 1311868253.408530 depth/1311868253.408530.png
1311868253.448691 rgb/1311868253.448691.png 1311868253.440717 depth/1311868253.440717.png
1311868253.480853 rgb/1311868253.480853.png 1311868253.474540 depth/1311868253.474540.png
1311868253.516704 rgb/1311868253.516704.png 1311868253.508676 depth/1311868253.508676.png
1311868253.548549 rgb/1311868253.548549.png 1311868253.539781 depth/1311868253.539781.png
1311868253.581530 rgb/1311868253.581530.png 1311868253.576628 depth/1311868253.576628.png
1311868253.616743 rgb/1311868253.616743.png 1311868253.606357 depth/1311868253.606357.png
1311868253.648742 rgb/1311868253.648742.png 1311868253.638854 depth/1311868253.638854.png
1311868253.680645 rgb/1311868253.680645.png 1311868253.675346 depth/1311868253.675346.png
1311868253.716771 rgb/1311868253.716771.png 1311868253.706080 depth/1311868253.706080.png
1311868253.748837 rgb/1311868253.748837.png 1311868253.738308 depth/1311868253.738308.png
1311868253.780775 rgb/1311868253.780775.png 1311868253.774636 depth/1311868253.774636.png
1311868253.816654 rgb/1311868253.816654.png 1311868253.806191 depth/1311868253.806191.png
1311868253.848746 rgb/1311868253.848746.png 1311868253.845257 depth/1311868253.845257.png
1311868253.880980 rgb/1311868253.880980.png 1311868253.874264 depth/1311868253.874264.png
1311868253.916916 rgb/1311868253.916916.png 1311868253.907739 depth/1311868253.907739.png
1311868253.948752 rgb/1311868253.948752.png 1311868253.942162 depth/1311868253.942162.png
1311868253.980731 rgb/1311868253.980731.png 1311868253.977273 depth/1311868253.977273.png
1311868254.016718 rgb/1311868254.016718.png 1311868254.009005 depth/1311868254.009005.png
1311868254.049168 rgb/1311868254.049168.png 1311868254.049214 depth/1311868254.049214.png
1311868254.080850 rgb/1311868254.080850.png 1311868254.078460 depth/1311868254.078460.png
1311868254.116780 rgb/1311868254.116780.png 1311868254.106940 depth/1311868254.106940.png
1311868254.148648 rgb/1311868254.148648.png 1311868254.142043 depth/1311868254.142043.png
1311868254.180791 rgb/1311868254.180791.png 1311868254.177201 depth/1311868254.177201.png
1311868254.216747 rgb/1311868254.216747.png 1311868254.206278 depth/1311868254.206278.png
1311868254.248926 rgb/1311868254.248926.png 1311868254.245618 depth/1311868254.245618.png
1311868254.281235 rgb/1311868254.281235.png 1311868254.275142 depth/1311868254.275142.png
1311868254.316692 rgb/1311868254.316692.png 1311868254.306491 depth/1311868254.306491.png
1311868254.348771 rgb/1311868254.348771.png 1311868254.346697 depth/1311868254.346697.png
1311868254.380853 rgb/1311868254.380853.png 1311868254.375530 depth/1311868254.375530.png
1311868254.416896 rgb/1311868254.416896.png 1311868254.406292 depth/1311868254.406292.png
1311868254.448907 rgb/1311868254.448907.png 1311868254.445676 depth/1311868254.445676.png
1311868254.481183 rgb/1311868254.481183.png 1311868254.476974 depth/1311868254.476974.png
1311868254.516676 rgb/1311868254.516676.png 1311868254.507711 depth/1311868254.507711.png
1311868254.548867 rgb/1311868254.548867.png 1311868254.543991 depth/1311868254.543991.png
1311868254.580918 rgb/1311868254.580918.png 1311868254.577386 depth/1311868254.577386.png
1311868254.616771 rgb/1311868254.616771.png 1311868254.606685 depth/1311868254.606685.png
1311868254.648657 rgb/1311868254.648657.png 1311868254.647558 depth/1311868254.647558.png
1311868254.680858 rgb/1311868254.680858.png 1311868254.677930 depth/1311868254.677930.png
1311868254.716785 rgb/1311868254.716785.png 1311868254.707057 depth/1311868254.707057.png
1311868254.748845 rgb/1311868254.748845.png 1311868254.742368 depth/1311868254.742368.png
1311868254.784875 rgb/1311868254.784875.png 1311868254.777541 depth/1311868254.777541.png
1311868254.816878 rgb/1311868254.816878.png 1311868254.809838 depth/1311868254.809838.png
1311868254.848916 rgb/1311868254.848916.png 1311868254.844351 depth/1311868254.844351.png
1311868254.885176 rgb/1311868254.885176.png 1311868254.879181 depth/1311868254.879181.png
1311868254.916952 rgb/1311868254.916952.png 1311868254.910622 depth/1311868254.910622.png
1311868254.948966 rgb/1311868254.948966.png 1311868254.942354 depth/1311868254.942354.png
1311868254.984826 rgb/1311868254.984826.png 1311868254.980186 depth/1311868254.980186.png
1311868255.016920 rgb/1311868255.016920.png 1311868255.013136 depth/1311868255.013136.png
1311868255.049320 rgb/1311868255.049320.png 1311868255.044172 depth/1311868255.044172.png
1311868255.084997 rgb/1311868255.084997.png 1311868255.074563 depth/1311868255.074563.png
1311868255.116728 rgb/1311868255.116728.png 1311868255.113381 depth/1311868255.113381.png
1311868255.148803 rgb/1311868255.148803.png 1311868255.145550 depth/1311868255.145550.png
1311868255.185128 rgb/1311868255.185128.png 1311868255.174737 depth/1311868255.174737.png
1311868255.216885 rgb/1311868255.216885.png 1311868255.213189 depth/1311868255.213189.png
1311868255.248740 rgb/1311868255.248740.png 1311868255.242406 depth/1311868255.242406.png
1311868255.285013 rgb/1311868255.285013.png 1311868255.276545 depth/1311868255.276545.png
1311868255.316993 rgb/1311868255.316993.png 1311868255.313626 depth/1311868255.313626.png
1311868255.349004 rgb/1311868255.349004.png 1311868255.345527 depth/1311868255.345527.png
1311868255.384831 rgb/1311868255.384831.png 1311868255.374387 depth/1311868255.374387.png
1311868255.417465 rgb/1311868255.417465.png 1311868255.411752 depth/1311868255.411752.png
1311868255.448957 rgb/1311868255.448957.png 1311868255.445257 depth/1311868255.445257.png
1311868255.484846 rgb/1311868255.484846.png 1311868255.476682 depth/1311868255.476682.png
1311868255.517093 rgb/1311868255.517093.png 1311868255.512434 depth/1311868255.512434.png
1311868255.548944 rgb/1311868255.548944.png 1311868255.542336 depth/1311868255.542336.png
1311868255.585756 rgb/1311868255.585756.png 1311868255.578739 depth/1311868255.578739.png
1311868255.616865 rgb/1311868255.616865.png 1311868255.616229 depth/1311868255.616229.png
1311868255.649271 rgb/1311868255.649271.png 1311868255.646008 depth/1311868255.646008.png
1311868255.684941 rgb/1311868255.684941.png 1311868255.675734 depth/1311868255.675734.png
1311868255.716862 rgb/1311868255.716862.png 1311868255.714709 depth/1311868255.714709.png
1311868255.748794 rgb/1311868255.748794.png 1311868255.742472 depth/1311868255.742472.png
1311868255.784952 rgb/1311868255.784952.png 1311868255.776905 depth/1311868255.776905.png
1311868255.817549 rgb/1311868255.817549.png 1311868255.814553 depth/1311868255.814553.png
1311868255.848787 rgb/1311868255.848787.png 1311868255.843682 depth/1311868255.843682.png
1311868255.884951 rgb/1311868255.884951.png 1311868255.875647 depth/1311868255.875647.png
1311868255.916866 rgb/1311868255.916866.png 1311868255.913435 depth/1311868255.913435.png
1311868255.948865 rgb/1311868255.948865.png 1311868255.942450 depth/1311868255.942450.png
1311868255.984771 rgb/1311868255.984771.png 1311868255.974226 depth/1311868255.974226.png
1311868256.017528 rgb/1311868256.017528.png 1311868256.017537 depth/1311868256.017537.png
1311868256.048877 rgb/1311868256.048877.png 1311868256.044139 depth/1311868256.044139.png
1311868256.084847 rgb/1311868256.084847.png 1311868256.075533 depth/1311868256.075533.png
1311868256.117284 rgb/1311868256.117284.png 1311868256.113864 depth/1311868256.113864.png
1311868256.149657 rgb/1311868256.149657.png 1311868256.145094 depth/1311868256.145094.png
1311868256.184808 rgb/1311868256.184808.png 1311868256.174467 depth/1311868256.174467.png
1311868256.216920 rgb/1311868256.216920.png 1311868256.214231 depth/1311868256.214231.png
1311868256.248884 rgb/1311868256.248884.png 1311868256.244139 depth/1311868256.244139.png
1311868256.284837 rgb/1311868256.284837.png 1311868256.279573 depth/1311868256.279573.png
1311868256.316827 rgb/1311868256.316827.png 1311868256.312468 depth/1311868256.312468.png
1311868256.348901 rgb/1311868256.348901.png 1311868256.346601 depth/1311868256.346601.png
1311868256.385489 rgb/1311868256.385489.png 1311868256.380368 depth/1311868256.380368.png
1311868256.417708 rgb/1311868256.417708.png 1311868256.417723 depth/1311868256.417723.png
1311868256.448918 rgb/1311868256.448918.png 1311868256.444304 depth/1311868256.444304.png
1311868256.484903 rgb/1311868256.484903.png 1311868256.481461 depth/1311868256.481461.png
1311868256.517192 rgb/1311868256.517192.png 1311868256.513423 depth/1311868256.513423.png
1311868256.548816 rgb/1311868256.548816.png 1311868256.542631 depth/1311868256.542631.png
1311868256.584898 rgb/1311868256.584898.png 1311868256.578502 depth/1311868256.578502.png
1311868256.616929 rgb/1311868256.616929.png 1311868256.612858 depth/1311868256.612858.png
1311868256.649078 rgb/1311868256.649078.png 1311868256.643525 depth/1311868256.643525.png
1311868256.684944 rgb/1311868256.684944.png 1311868256.680977 depth/1311868256.680977.png
1311868256.717133 rgb/1311868256.717133.png 1311868256.715852 depth/1311868256.715852.png
1311868256.749056 rgb/1311868256.749056.png 1311868256.742686 depth/1311868256.742686.png
1311868256.785171 rgb/1311868256.785171.png 1311868256.781989 depth/1311868256.781989.png
1311868256.816832 rgb/1311868256.816832.png 1311868256.815457 depth/1311868256.815457.png
1311868256.848894 rgb/1311868256.848894.png 1311868256.843853 depth/1311868256.843853.png
1311868256.885027 rgb/1311868256.885027.png 1311868256.881870 depth/1311868256.881870.png
1311868256.916906 rgb/1311868256.916906.png 1311868256.910285 depth/1311868256.910285.png
1311868256.949184 rgb/1311868256.949184.png 1311868256.943253 depth/1311868256.943253.png
1311868256.984945 rgb/1311868256.984945.png 1311868256.979646 depth/1311868256.979646.png
1311868257.017144 rgb/1311868257.017144.png 1311868257.010623 depth/1311868257.010623.png
1311868257.049224 rgb/1311868257.049224.png 1311868257.046340 depth/1311868257.046340.png
1311868257.085190 rgb/1311868257.085190.png 1311868257.081240 depth/1311868257.081240.png
1311868257.116964 rgb/1311868257.116964.png 1311868257.110972 depth/1311868257.110972.png
1311868257.149165 rgb/1311868257.149165.png 1311868257.145087 depth/1311868257.145087.png
1311868257.184982 rgb/1311868257.184982.png 1311868257.182971 depth/1311868257.182971.png
1311868257.216830 rgb/1311868257.216830.png 1311868257.211776 depth/1311868257.211776.png
1311868257.248914 rgb/1311868257.248914.png 1311868257.244222 depth/1311868257.244222.png
1311868257.284925 rgb/1311868257.284925.png 1311868257.278283 depth/1311868257.278283.png
1311868257.317019 rgb/1311868257.317019.png 1311868257.311876 depth/1311868257.311876.png
1311868257.348967 rgb/1311868257.348967.png 1311868257.344870 depth/1311868257.344870.png
1311868257.384936 rgb/1311868257.384936.png 1311868257.378252 depth/1311868257.378252.png
1311868257.416835 rgb/1311868257.416835.png 1311868257.410362 depth/1311868257.410362.png
1311868257.449069 rgb/1311868257.449069.png 1311868257.445493 depth/1311868257.445493.png
1311868257.485023 rgb/1311868257.485023.png 1311868257.478276 depth/1311868257.478276.png
1311868257.516816 rgb/1311868257.516816.png 1311868257.510320 depth/1311868257.510320.png
1311868257.549492 rgb/1311868257.549492.png 1311868257.549508 depth/1311868257.549508.png
1311868257.585336 rgb/1311868257.585336.png 1311868257.580687 depth/1311868257.580687.png
1311868257.617970 rgb/1311868257.617970.png 1311868257.613445 depth/1311868257.613445.png
1311868257.649061 rgb/1311868257.649061.png 1311868257.649072 depth/1311868257.649072.png
1311868257.684916 rgb/1311868257.684916.png 1311868257.679183 depth/1311868257.679183.png
1311868257.717951 rgb/1311868257.717951.png 1311868257.713715 depth/1311868257.713715.png
1311868257.749626 rgb/1311868257.749626.png 1311868257.746865 depth/1311868257.746865.png
1311868257.785459 rgb/1311868257.785459.png 1311868257.780361 depth/1311868257.780361.png
1311868257.816852 rgb/1311868257.816852.png 1311868257.812435 depth/1311868257.812435.png
1311868257.849241 rgb/1311868257.849241.png 1311868257.848216 depth/1311868257.848216.png
1311868257.885261 rgb/1311868257.885261.png 1311868257.878977 depth/1311868257.878977.png
1311868257.917005 rgb/1311868257.917005.png 1311868257.910339 depth/1311868257.910339.png
1311868257.949031 rgb/1311868257.949031.png 1311868257.946098 depth/1311868257.946098.png
1311868257.985217 rgb/1311868257.985217.png 1311868257.981851 depth/1311868257.981851.png
1311868258.016837 rgb/1311868258.016837.png 1311868258.011809 depth/1311868258.011809.png
1311868258.048909 rgb/1311868258.048909.png 1311868258.047417 depth/1311868258.047417.png
1311868258.086178 rgb/1311868258.086178.png 1311868258.080461 depth/1311868258.080461.png
1311868258.117570 rgb/1311868258.117570.png 1311868258.112975 depth/1311868258.112975.png
1311868258.149278 rgb/1311868258.149278.png 1311868258.149289 depth/1311868258.149289.png
1311868258.185124 rgb/1311868258.185124.png 1311868258.178249 depth/1311868258.178249.png
1311868258.216937 rgb/1311868258.216937.png 1311868258.212794 depth/1311868258.212794.png
1311868258.251845 rgb/1311868258.251845.png 1311868258.251851 depth/1311868258.251851.png
1311868258.285207 rgb/1311868258.285207.png 1311868258.281239 depth/1311868258.281239.png
1311868258.317231 rgb/1311868258.317231.png 1311868258.310618 depth/1311868258.310618.png
1311868258.349077 rgb/1311868258.349077.png 1311868258.346583 depth/1311868258.346583.png
1311868258.384969 rgb/1311868258.384969.png 1311868258.378857 depth/1311868258.378857.png
1311868258.416975 rgb/1311868258.416975.png 1311868258.412501 depth/1311868258.412501.png
1311868258.449148 rgb/1311868258.449148.png 1311868258.446276 depth/1311868258.446276.png
1311868258.484910 rgb/1311868258.484910.png 1311868258.478853 depth/1311868258.478853.png
1311868258.517262 rgb/1311868258.517262.png 1311868258.511933 depth/1311868258.511933.png
1311868258.549307 rgb/1311868258.549307.png 1311868258.549314 depth/1311868258.549314.png
1311868258.585124 rgb/1311868258.585124.png 1311868258.579437 depth/1311868258.579437.png
1311868258.616904 rgb/1311868258.616904.png 1311868258.610780 depth/1311868258.610780.png
1311868258.648890 rgb/1311868258.648890.png 1311868258.647483 depth/1311868258.647483.png
1311868258.685108 rgb/1311868258.685108.png 1311868258.680659 depth/1311868258.680659.png
1311868258.716929 rgb/1311868258.716929.png 1311868258.714945 depth/1311868258.714945.png
1311868258.749015 rgb/1311868258.749015.png 1311868258.746669 depth/1311868258.746669.png
1311868258.785039 rgb/1311868258.785039.png 1311868258.778477 depth/1311868258.778477.png
1311868258.817013 rgb/1311868258.817013.png 1311868258.817027 depth/1311868258.817027.png
1311868258.848932 rgb/1311868258.848932.png 1311868258.848121 depth/1311868258.848121.png
1311868258.885648 rgb/1311868258.885648.png 1311868258.880629 depth/1311868258.880629.png
1311868258.917705 rgb/1311868258.917705.png 1311868258.917712 depth/1311868258.917712.png
1311868258.949852 rgb/1311868258.949852.png 1311868258.952816 depth/1311868258.952816.png
1311868258.985070 rgb/1311868258.985070.png 1311868258.979187 depth/1311868258.979187.png
1311868259.017026 rgb/1311868259.017026.png 1311868259.015276 depth/1311868259.015276.png
1311868259.048922 rgb/1311868259.048922.png 1311868259.046173 depth/1311868259.046173.png
1311868259.085232 rgb/1311868259.085232.png 1311868259.078286 depth/1311868259.078286.png
1311868259.116919 rgb/1311868259.116919.png 1311868259.116291 depth/1311868259.116291.png
1311868259.149197 rgb/1311868259.149197.png 1311868259.146207 depth/1311868259.146207.png
1311868259.185707 rgb/1311868259.185707.png 1311868259.179623 depth/1311868259.179623.png
1311868259.216979 rgb/1311868259.216979.png 1311868259.215477 depth/1311868259.215477.png
1311868259.248996 rgb/1311868259.248996.png 1311868259.249045 depth/1311868259.249045.png
1311868259.285039 rgb/1311868259.285039.png 1311868259.278157 depth/1311868259.278157.png
1311868259.316960 rgb/1311868259.316960.png 1311868259.316647 depth/1311868259.316647.png
1311868259.350162 rgb/1311868259.350162.png 1311868259.347717 depth/1311868259.347717.png
1311868259.385116 rgb/1311868259.385116.png 1311868259.378293 depth/1311868259.378293.png
1311868259.417128 rgb/1311868259.417128.png 1311868259.414464 depth/1311868259.414464.png
1311868259.449140 rgb/1311868259.449140.png 1311868259.446253 depth/1311868259.446253.png
1311868259.485201 rgb/1311868259.485201.png 1311868259.478144 depth/1311868259.478144.png
1311868259.517235 rgb/1311868259.517235.png 1311868259.515800 depth/1311868259.515800.png
1311868259.549524 rgb/1311868259.549524.png 1311868259.546344 depth/1311868259.546344.png
1311868259.585081 rgb/1311868259.585081.png 1311868259.578929 depth/1311868259.578929.png
1311868259.617127 rgb/1311868259.617127.png 1311868259.614250 depth/1311868259.614250.png
1311868259.649289 rgb/1311868259.649289.png 1311868259.649301 depth/1311868259.649301.png
1311868259.685014 rgb/1311868259.685014.png 1311868259.678658 depth/1311868259.678658.png
1311868259.717139 rgb/1311868259.717139.png 1311868259.714458 depth/1311868259.714458.png
1311868259.749049 rgb/1311868259.749049.png 1311868259.746178 depth/1311868259.746178.png
1311868259.785037 rgb/1311868259.785037.png 1311868259.778932 depth/1311868259.778932.png
1311868259.818043 rgb/1311868259.818043.png 1311868259.818056 depth/1311868259.818056.png
1311868259.849187 rgb/1311868259.849187.png 1311868259.846243 depth/1311868259.846243.png
1311868259.885215 rgb/1311868259.885215.png 1311868259.878572 depth/1311868259.878572.png
1311868259.917493 rgb/1311868259.917493.png 1311868259.917515 depth/1311868259.917515.png
1311868259.949104 rgb/1311868259.949104.png 1311868259.946174 depth/1311868259.946174.png
1311868259.984972 rgb/1311868259.984972.png 1311868259.983338 depth/1311868259.983338.png
1311868260.017107 rgb/1311868260.017107.png 1311868260.014161 depth/1311868260.014161.png
1311868260.049125 rgb/1311868260.049125.png 1311868260.048211 depth/1311868260.048211.png
1311868260.085277 rgb/1311868260.085277.png 1311868260.082184 depth/1311868260.082184.png
1311868260.116985 rgb/1311868260.116985.png 1311868260.114743 depth/1311868260.114743.png
1311868260.149117 rgb/1311868260.149117.png 1311868260.146239 depth/1311868260.146239.png
1311868260.184916 rgb/1311868260.184916.png 1311868260.183834 depth/1311868260.183834.png
1311868260.217009 rgb/1311868260.217009.png 1311868260.214450 depth/1311868260.214450.png
1311868260.249110 rgb/1311868260.249110.png 1311868260.246542 depth/1311868260.246542.png
1311868260.285037 rgb/1311868260.285037.png 1311868260.284135 depth/1311868260.284135.png
1311868260.317238 rgb/1311868260.317238.png 1311868260.315778 depth/1311868260.315778.png
1311868260.349210 rgb/1311868260.349210.png 1311868260.346391 depth/1311868260.346391.png
1311868260.385901 rgb/1311868260.385901.png 1311868260.385908 depth/1311868260.385908.png
1311868260.417177 rgb/1311868260.417177.png 1311868260.414797 depth/1311868260.414797.png
1311868260.449188 rgb/1311868260.449188.png 1311868260.446575 depth/1311868260.446575.png
1311868260.485105 rgb/1311868260.485105.png 1311868260.482440 depth/1311868260.482440.png
1311868260.517155 rgb/1311868260.517155.png 1311868260.514754 depth/1311868260.514754.png
1311868260.549278 rgb/1311868260.549278.png 1311868260.546370 depth/1311868260.546370.png
1311868260.588498 rgb/1311868260.588498.png 1311868260.588507 depth/1311868260.588507.png
1311868260.617023 rgb/1311868260.617023.png 1311868260.615833 depth/1311868260.615833.png
1311868260.649220 rgb/1311868260.649220.png 1311868260.646588 depth/1311868260.646588.png
1311868260.685161 rgb/1311868260.685161.png 1311868260.682811 depth/1311868260.682811.png
1311868260.717031 rgb/1311868260.717031.png 1311868260.715415 depth/1311868260.715415.png
1311868260.749052 rgb/1311868260.749052.png 1311868260.746446 depth/1311868260.746446.png
1311868260.785032 rgb/1311868260.785032.png 1311868260.783695 depth/1311868260.783695.png
1311868260.817354 rgb/1311868260.817354.png 1311868260.815058 depth/1311868260.815058.png
1311868260.849412 rgb/1311868260.849412.png 1311868260.846558 depth/1311868260.846558.png
1311868260.885138 rgb/1311868260.885138.png 1311868260.882914 depth/1311868260.882914.png
1311868260.917044 rgb/1311868260.917044.png 1311868260.914428 depth/1311868260.914428.png
1311868260.949176 rgb/1311868260.949176.png 1311868260.946230 depth/1311868260.946230.png
1311868260.985735 rgb/1311868260.985735.png 1311868260.982386 depth/1311868260.982386.png
1311868261.017109 rgb/1311868261.017109.png 1311868261.014265 depth/1311868261.014265.png
1311868261.049410 rgb/1311868261.049410.png 1311868261.046223 depth/1311868261.046223.png
1311868261.085064 rgb/1311868261.085064.png 1311868261.082974 depth/1311868261.082974.png
1311868261.117521 rgb/1311868261.117521.png 1311868261.114432 depth/1311868261.114432.png
1311868261.149243 rgb/1311868261.149243.png 1311868261.146208 depth/1311868261.146208.png
1311868261.185057 rgb/1311868261.185057.png 1311868261.182814 depth/1311868261.182814.png
1311868261.217343 rgb/1311868261.217343.png 1311868261.214895 depth/1311868261.214895.png
1311868261.250674 rgb/1311868261.250674.png 1311868261.250688 depth/1311868261.250688.png
1311868261.285209 rgb/1311868261.285209.png 1311868261.282599 depth/1311868261.282599.png
1311868261.317339 rgb/1311868261.317339.png 1311868261.315052 depth/1311868261.315052.png
1311868261.350547 rgb/1311868261.350547.png 1311868261.350587 depth/1311868261.350587.png
1311868261.385162 rgb/1311868261.385162.png 1311868261.383099 depth/1311868261.383099.png
1311868261.417214 rgb/1311868261.417214.png 1311868261.414396 depth/1311868261.414396.png
1311868261.450926 rgb/1311868261.450926.png 1311868261.451520 depth/1311868261.451520.png
1311868261.485265 rgb/1311868261.485265.png 1311868261.485277 depth/1311868261.485277.png
1311868261.517293 rgb/1311868261.517293.png 1311868261.515046 depth/1311868261.515046.png
1311868261.553565 rgb/1311868261.553565.png 1311868261.553583 depth/1311868261.553583.png
1311868261.586338 rgb/1311868261.586338.png 1311868261.586519 depth/1311868261.586519.png
1311868261.617239 rgb/1311868261.617239.png 1311868261.614699 depth/1311868261.614699.png
1311868261.654121 rgb/1311868261.654121.png 1311868261.654137 depth/1311868261.654137.png
1311868261.685195 rgb/1311868261.685195.png 1311868261.684839 depth/1311868261.684839.png
1311868261.719495 rgb/1311868261.719495.png 1311868261.719540 depth/1311868261.719540.png
1311868261.751682 rgb/1311868261.751682.png 1311868261.751691 depth/1311868261.751691.png
1311868261.787133 rgb/1311868261.787133.png 1311868261.787339 depth/1311868261.787339.png
1311868261.817195 rgb/1311868261.817195.png 1311868261.815089 depth/1311868261.815089.png
1311868261.853032 rgb/1311868261.853032.png 1311868261.853042 depth/1311868261.853042.png
1311868261.885094 rgb/1311868261.885094.png 1311868261.884022 depth/1311868261.884022.png
1311868261.917121 rgb/1311868261.917121.png 1311868261.916925 depth/1311868261.916925.png
1311868261.953503 rgb/1311868261.953503.png 1311868261.957504 depth/1311868261.957504.png
1311868261.985273 rgb/1311868261.985273.png 1311868261.982533 depth/1311868261.982533.png
1311868262.018018 rgb/1311868262.018018.png 1311868262.014541 depth/1311868262.014541.png
1311868262.053615 rgb/1311868262.053615.png 1311868262.053641 depth/1311868262.053641.png
1311868262.085382 rgb/1311868262.085382.png 1311868262.082463 depth/1311868262.082463.png
1311868262.117887 rgb/1311868262.117887.png 1311868262.117904 depth/1311868262.117904.png
1311868262.150528 rgb/1311868262.150528.png 1311868262.150538 depth/1311868262.150538.png
1311868262.185453 rgb/1311868262.185453.png 1311868262.185471 depth/1311868262.185471.png
1311868262.217304 rgb/1311868262.217304.png 1311868262.214323 depth/1311868262.214323.png
1311868262.253167 rgb/1311868262.253167.png 1311868262.253178 depth/1311868262.253178.png
1311868262.287398 rgb/1311868262.287398.png 1311868262.287414 depth/1311868262.287414.png
1311868262.317336 rgb/1311868262.317336.png 1311868262.315421 depth/1311868262.315421.png
1311868262.351121 rgb/1311868262.351121.png 1311868262.351149 depth/1311868262.351149.png
1311868262.386061 rgb/1311868262.386061.png 1311868262.386104 depth/1311868262.386104.png
1311868262.419248 rgb/1311868262.419248.png 1311868262.419289 depth/1311868262.419289.png
1311868262.453041 rgb/1311868262.453041.png 1311868262.453084 depth/1311868262.453084.png
1311868262.485168 rgb/1311868262.485168.png 1311868262.483233 depth/1311868262.483233.png
1311868262.521495 rgb/1311868262.521495.png 1311868262.521526 depth/1311868262.521526.png
1311868262.550967 rgb/1311868262.550967.png 1311868262.550977 depth/1311868262.550977.png
1311868262.585111 rgb/1311868262.585111.png 1311868262.583605 depth/1311868262.583605.png
1311868262.621668 rgb/1311868262.621668.png 1311868262.621716 depth/1311868262.621716.png
1311868262.650784 rgb/1311868262.650784.png 1311868262.650793 depth/1311868262.650793.png
1311868262.685330 rgb/1311868262.685330.png 1311868262.682453 depth/1311868262.682453.png
1311868262.721190 rgb/1311868262.721190.png 1311868262.721201 depth/1311868262.721201.png
1311868262.750486 rgb/1311868262.750486.png 1311868262.750492 depth/1311868262.750492.png
1311868262.785224 rgb/1311868262.785224.png 1311868262.783129 depth/1311868262.783129.png
1311868262.821620 rgb/1311868262.821620.png 1311868262.821651 depth/1311868262.821651.png
1311868262.850602 rgb/1311868262.850602.png 1311868262.850608 depth/1311868262.850608.png
1311868262.885337 rgb/1311868262.885337.png 1311868262.884225 depth/1311868262.884225.png
1311868262.922678 rgb/1311868262.922678.png 1311868262.922686 depth/1311868262.922686.png
1311868262.950706 rgb/1311868262.950706.png 1311868262.950713 depth/1311868262.950713.png
1311868262.985587 rgb/1311868262.985587.png 1311868262.985630 depth/1311868262.985630.png
1311868263.020693 rgb/1311868263.020693.png 1311868263.020700 depth/1311868263.020700.png
1311868263.053350 rgb/1311868263.053350.png 1311868263.053360 depth/1311868263.053360.png
1311868263.085224 rgb/1311868263.085224.png 1311868263.082803 depth/1311868263.082803.png
1311868263.121396 rgb/1311868263.121396.png 1311868263.121413 depth/1311868263.121413.png
1311868263.154334 rgb/1311868263.154334.png 1311868263.154346 depth/1311868263.154346.png
1311868263.185529 rgb/1311868263.185529.png 1311868263.184152 depth/1311868263.184152.png
================================================
FILE: Examples/RGB-D/associations/fr2_xyz.txt
================================================
1311867170.462290 rgb/1311867170.462290.png 1311867170.450076 depth/1311867170.450076.png
1311867170.494139 rgb/1311867170.494139.png 1311867170.483500 depth/1311867170.483500.png
1311867170.526429 rgb/1311867170.526429.png 1311867170.516818 depth/1311867170.516818.png
1311867170.562349 rgb/1311867170.562349.png 1311867170.551384 depth/1311867170.551384.png
1311867170.594217 rgb/1311867170.594217.png 1311867170.580990 depth/1311867170.580990.png
1311867170.626087 rgb/1311867170.626087.png 1311867170.617942 depth/1311867170.617942.png
1311867170.662140 rgb/1311867170.662140.png 1311867170.649674 depth/1311867170.649674.png
1311867170.694205 rgb/1311867170.694205.png 1311867170.680532 depth/1311867170.680532.png
1311867170.726388 rgb/1311867170.726388.png 1311867170.717358 depth/1311867170.717358.png
1311867170.762019 rgb/1311867170.762019.png 1311867170.749451 depth/1311867170.749451.png
1311867170.794192 rgb/1311867170.794192.png 1311867170.780364 depth/1311867170.780364.png
1311867170.826282 rgb/1311867170.826282.png 1311867170.816535 depth/1311867170.816535.png
1311867170.862221 rgb/1311867170.862221.png 1311867170.850616 depth/1311867170.850616.png
1311867170.894378 rgb/1311867170.894378.png 1311867170.882672 depth/1311867170.882672.png
1311867170.926352 rgb/1311867170.926352.png 1311867170.917264 depth/1311867170.917264.png
1311867170.962147 rgb/1311867170.962147.png 1311867170.949643 depth/1311867170.949643.png
1311867170.994263 rgb/1311867170.994263.png 1311867170.986197 depth/1311867170.986197.png
1311867171.026274 rgb/1311867171.026274.png 1311867171.019831 depth/1311867171.019831.png
1311867171.062352 rgb/1311867171.062352.png 1311867171.052592 depth/1311867171.052592.png
1311867171.094235 rgb/1311867171.094235.png 1311867171.084303 depth/1311867171.084303.png
1311867171.126251 rgb/1311867171.126251.png 1311867171.116865 depth/1311867171.116865.png
1311867171.162247 rgb/1311867171.162247.png 1311867171.150265 depth/1311867171.150265.png
1311867171.194269 rgb/1311867171.194269.png 1311867171.188157 depth/1311867171.188157.png
1311867171.226253 rgb/1311867171.226253.png 1311867171.215808 depth/1311867171.215808.png
1311867171.262244 rgb/1311867171.262244.png 1311867171.250755 depth/1311867171.250755.png
1311867171.294341 rgb/1311867171.294341.png 1311867171.288603 depth/1311867171.288603.png
1311867171.326387 rgb/1311867171.326387.png 1311867171.320387 depth/1311867171.320387.png
1311867171.362246 rgb/1311867171.362246.png 1311867171.348416 depth/1311867171.348416.png
1311867171.394143 rgb/1311867171.394143.png 1311867171.386411 depth/1311867171.386411.png
1311867171.426288 rgb/1311867171.426288.png 1311867171.418257 depth/1311867171.418257.png
1311867171.462244 rgb/1311867171.462244.png 1311867171.450724 depth/1311867171.450724.png
1311867171.494404 rgb/1311867171.494404.png 1311867171.485965 depth/1311867171.485965.png
1311867171.526178 rgb/1311867171.526178.png 1311867171.516537 depth/1311867171.516537.png
1311867171.562297 rgb/1311867171.562297.png 1311867171.552054 depth/1311867171.552054.png
1311867171.594293 rgb/1311867171.594293.png 1311867171.587078 depth/1311867171.587078.png
1311867171.626340 rgb/1311867171.626340.png 1311867171.619828 depth/1311867171.619828.png
1311867171.662256 rgb/1311867171.662256.png 1311867171.651108 depth/1311867171.651108.png
1311867171.694344 rgb/1311867171.694344.png 1311867171.685447 depth/1311867171.685447.png
1311867171.726244 rgb/1311867171.726244.png 1311867171.716495 depth/1311867171.716495.png
1311867171.762119 rgb/1311867171.762119.png 1311867171.752030 depth/1311867171.752030.png
1311867171.794171 rgb/1311867171.794171.png 1311867171.787543 depth/1311867171.787543.png
1311867171.826255 rgb/1311867171.826255.png 1311867171.816493 depth/1311867171.816493.png
1311867171.862359 rgb/1311867171.862359.png 1311867171.852528 depth/1311867171.852528.png
1311867171.894443 rgb/1311867171.894443.png 1311867171.887719 depth/1311867171.887719.png
1311867171.926222 rgb/1311867171.926222.png 1311867171.916475 depth/1311867171.916475.png
1311867171.962467 rgb/1311867171.962467.png 1311867171.951952 depth/1311867171.951952.png
1311867171.994671 rgb/1311867171.994671.png 1311867171.988074 depth/1311867171.988074.png
1311867172.026268 rgb/1311867172.026268.png 1311867172.016436 depth/1311867172.016436.png
1311867172.062288 rgb/1311867172.062288.png 1311867172.049438 depth/1311867172.049438.png
1311867172.094196 rgb/1311867172.094196.png 1311867172.088132 depth/1311867172.088132.png
1311867172.126369 rgb/1311867172.126369.png 1311867172.117248 depth/1311867172.117248.png
1311867172.162335 rgb/1311867172.162335.png 1311867172.152282 depth/1311867172.152282.png
1311867172.194427 rgb/1311867172.194427.png 1311867172.188469 depth/1311867172.188469.png
1311867172.226441 rgb/1311867172.226441.png 1311867172.219929 depth/1311867172.219929.png
1311867172.262228 rgb/1311867172.262228.png 1311867172.252969 depth/1311867172.252969.png
1311867172.294483 rgb/1311867172.294483.png 1311867172.286931 depth/1311867172.286931.png
1311867172.326338 rgb/1311867172.326338.png 1311867172.318507 depth/1311867172.318507.png
1311867172.362401 rgb/1311867172.362401.png 1311867172.355461 depth/1311867172.355461.png
1311867172.394289 rgb/1311867172.394289.png 1311867172.387297 depth/1311867172.387297.png
1311867172.426522 rgb/1311867172.426522.png 1311867172.417192 depth/1311867172.417192.png
1311867172.462350 rgb/1311867172.462350.png 1311867172.455419 depth/1311867172.455419.png
1311867172.495267 rgb/1311867172.495267.png 1311867172.487872 depth/1311867172.487872.png
1311867172.526306 rgb/1311867172.526306.png 1311867172.517723 depth/1311867172.517723.png
1311867172.562493 rgb/1311867172.562493.png 1311867172.556634 depth/1311867172.556634.png
1311867172.594544 rgb/1311867172.594544.png 1311867172.589554 depth/1311867172.589554.png
1311867172.626370 rgb/1311867172.626370.png 1311867172.618563 depth/1311867172.618563.png
1311867172.662442 rgb/1311867172.662442.png 1311867172.652198 depth/1311867172.652198.png
1311867172.694545 rgb/1311867172.694545.png 1311867172.686797 depth/1311867172.686797.png
1311867172.726393 rgb/1311867172.726393.png 1311867172.716473 depth/1311867172.716473.png
1311867172.762374 rgb/1311867172.762374.png 1311867172.755581 depth/1311867172.755581.png
1311867172.794451 rgb/1311867172.794451.png 1311867172.784603 depth/1311867172.784603.png
1311867172.826309 rgb/1311867172.826309.png 1311867172.819640 depth/1311867172.819640.png
1311867172.863231 rgb/1311867172.863231.png 1311867172.856187 depth/1311867172.856187.png
1311867172.894465 rgb/1311867172.894465.png 1311867172.888261 depth/1311867172.888261.png
1311867172.926322 rgb/1311867172.926322.png 1311867172.920135 depth/1311867172.920135.png
1311867172.962331 rgb/1311867172.962331.png 1311867172.955319 depth/1311867172.955319.png
1311867172.994527 rgb/1311867172.994527.png 1311867172.987530 depth/1311867172.987530.png
1311867173.026263 rgb/1311867173.026263.png 1311867173.016636 depth/1311867173.016636.png
1311867173.062463 rgb/1311867173.062463.png 1311867173.055015 depth/1311867173.055015.png
1311867173.094518 rgb/1311867173.094518.png 1311867173.085411 depth/1311867173.085411.png
1311867173.126782 rgb/1311867173.126782.png 1311867173.118688 depth/1311867173.118688.png
1311867173.162231 rgb/1311867173.162231.png 1311867173.152903 depth/1311867173.152903.png
1311867173.194301 rgb/1311867173.194301.png 1311867173.186066 depth/1311867173.186066.png
1311867173.226445 rgb/1311867173.226445.png 1311867173.217457 depth/1311867173.217457.png
1311867173.262202 rgb/1311867173.262202.png 1311867173.252384 depth/1311867173.252384.png
1311867173.294268 rgb/1311867173.294268.png 1311867173.286128 depth/1311867173.286128.png
1311867173.326288 rgb/1311867173.326288.png 1311867173.316543 depth/1311867173.316543.png
1311867173.362328 rgb/1311867173.362328.png 1311867173.355753 depth/1311867173.355753.png
1311867173.394287 rgb/1311867173.394287.png 1311867173.384413 depth/1311867173.384413.png
1311867173.426279 rgb/1311867173.426279.png 1311867173.416714 depth/1311867173.416714.png
1311867173.462290 rgb/1311867173.462290.png 1311867173.455557 depth/1311867173.455557.png
1311867173.494339 rgb/1311867173.494339.png 1311867173.484349 depth/1311867173.484349.png
1311867173.526390 rgb/1311867173.526390.png 1311867173.521797 depth/1311867173.521797.png
1311867173.562437 rgb/1311867173.562437.png 1311867173.552167 depth/1311867173.552167.png
1311867173.594311 rgb/1311867173.594311.png 1311867173.584281 depth/1311867173.584281.png
1311867173.626396 rgb/1311867173.626396.png 1311867173.622125 depth/1311867173.622125.png
1311867173.662330 rgb/1311867173.662330.png 1311867173.652630 depth/1311867173.652630.png
1311867173.694354 rgb/1311867173.694354.png 1311867173.686190 depth/1311867173.686190.png
1311867173.726797 rgb/1311867173.726797.png 1311867173.721725 depth/1311867173.721725.png
1311867173.762397 rgb/1311867173.762397.png 1311867173.756464 depth/1311867173.756464.png
1311867173.794356 rgb/1311867173.794356.png 1311867173.785162 depth/1311867173.785162.png
1311867173.826567 rgb/1311867173.826567.png 1311867173.821195 depth/1311867173.821195.png
1311867173.863580 rgb/1311867173.863580.png 1311867173.852567 depth/1311867173.852567.png
1311867173.894608 rgb/1311867173.894608.png 1311867173.884587 depth/1311867173.884587.png
1311867173.926697 rgb/1311867173.926697.png 1311867173.921914 depth/1311867173.921914.png
1311867173.962546 rgb/1311867173.962546.png 1311867173.953686 depth/1311867173.953686.png
1311867173.994431 rgb/1311867173.994431.png 1311867173.989219 depth/1311867173.989219.png
1311867174.026426 rgb/1311867174.026426.png 1311867174.024019 depth/1311867174.024019.png
1311867174.062463 rgb/1311867174.062463.png 1311867174.054183 depth/1311867174.054183.png
1311867174.094519 rgb/1311867174.094519.png 1311867174.086830 depth/1311867174.086830.png
1311867174.126454 rgb/1311867174.126454.png 1311867174.124495 depth/1311867174.124495.png
1311867174.162433 rgb/1311867174.162433.png 1311867174.155288 depth/1311867174.155288.png
1311867174.194398 rgb/1311867174.194398.png 1311867174.184582 depth/1311867174.184582.png
1311867174.226758 rgb/1311867174.226758.png 1311867174.220459 depth/1311867174.220459.png
1311867174.262677 rgb/1311867174.262677.png 1311867174.252364 depth/1311867174.252364.png
1311867174.294528 rgb/1311867174.294528.png 1311867174.285999 depth/1311867174.285999.png
1311867174.326574 rgb/1311867174.326574.png 1311867174.323248 depth/1311867174.323248.png
1311867174.362433 rgb/1311867174.362433.png 1311867174.354525 depth/1311867174.354525.png
1311867174.394636 rgb/1311867174.394636.png 1311867174.385575 depth/1311867174.385575.png
1311867174.426679 rgb/1311867174.426679.png 1311867174.420747 depth/1311867174.420747.png
1311867174.463016 rgb/1311867174.463016.png 1311867174.456817 depth/1311867174.456817.png
1311867174.494567 rgb/1311867174.494567.png 1311867174.484843 depth/1311867174.484843.png
1311867174.526752 rgb/1311867174.526752.png 1311867174.523854 depth/1311867174.523854.png
1311867174.562350 rgb/1311867174.562350.png 1311867174.552584 depth/1311867174.552584.png
1311867174.594488 rgb/1311867174.594488.png 1311867174.587453 depth/1311867174.587453.png
1311867174.626546 rgb/1311867174.626546.png 1311867174.620460 depth/1311867174.620460.png
1311867174.662491 rgb/1311867174.662491.png 1311867174.657131 depth/1311867174.657131.png
1311867174.694591 rgb/1311867174.694591.png 1311867174.689552 depth/1311867174.689552.png
1311867174.726563 rgb/1311867174.726563.png 1311867174.720531 depth/1311867174.720531.png
1311867174.762376 rgb/1311867174.762376.png 1311867174.755617 depth/1311867174.755617.png
1311867174.794474 rgb/1311867174.794474.png 1311867174.791669 depth/1311867174.791669.png
1311867174.827330 rgb/1311867174.827330.png 1311867174.827340 depth/1311867174.827340.png
1311867174.862423 rgb/1311867174.862423.png 1311867174.852853 depth/1311867174.852853.png
1311867174.894420 rgb/1311867174.894420.png 1311867174.892876 depth/1311867174.892876.png
1311867174.926975 rgb/1311867174.926975.png 1311867174.927018 depth/1311867174.927018.png
1311867174.962643 rgb/1311867174.962643.png 1311867174.954480 depth/1311867174.954480.png
1311867174.994335 rgb/1311867174.994335.png 1311867174.993193 depth/1311867174.993193.png
1311867175.026551 rgb/1311867175.026551.png 1311867175.020706 depth/1311867175.020706.png
1311867175.063312 rgb/1311867175.063312.png 1311867175.057641 depth/1311867175.057641.png
1311867175.094719 rgb/1311867175.094719.png 1311867175.091331 depth/1311867175.091331.png
1311867175.126531 rgb/1311867175.126531.png 1311867175.120766 depth/1311867175.120766.png
1311867175.162518 rgb/1311867175.162518.png 1311867175.156149 depth/1311867175.156149.png
1311867175.194640 rgb/1311867175.194640.png 1311867175.188878 depth/1311867175.188878.png
1311867175.227005 rgb/1311867175.227005.png 1311867175.220693 depth/1311867175.220693.png
1311867175.262467 rgb/1311867175.262467.png 1311867175.252815 depth/1311867175.252815.png
1311867175.294451 rgb/1311867175.294451.png 1311867175.289629 depth/1311867175.289629.png
1311867175.326706 rgb/1311867175.326706.png 1311867175.323775 depth/1311867175.323775.png
1311867175.362565 rgb/1311867175.362565.png 1311867175.353647 depth/1311867175.353647.png
1311867175.394599 rgb/1311867175.394599.png 1311867175.388820 depth/1311867175.388820.png
1311867175.426606 rgb/1311867175.426606.png 1311867175.423375 depth/1311867175.423375.png
1311867175.462600 rgb/1311867175.462600.png 1311867175.454628 depth/1311867175.454628.png
1311867175.494573 rgb/1311867175.494573.png 1311867175.488524 depth/1311867175.488524.png
1311867175.526427 rgb/1311867175.526427.png 1311867175.520404 depth/1311867175.520404.png
1311867175.562570 rgb/1311867175.562570.png 1311867175.555278 depth/1311867175.555278.png
1311867175.594664 rgb/1311867175.594664.png 1311867175.588623 depth/1311867175.588623.png
1311867175.626480 rgb/1311867175.626480.png 1311867175.622267 depth/1311867175.622267.png
1311867175.662493 rgb/1311867175.662493.png 1311867175.652465 depth/1311867175.652465.png
1311867175.694700 rgb/1311867175.694700.png 1311867175.691635 depth/1311867175.691635.png
1311867175.727312 rgb/1311867175.727312.png 1311867175.720574 depth/1311867175.720574.png
1311867175.762497 rgb/1311867175.762497.png 1311867175.752846 depth/1311867175.752846.png
1311867175.794862 rgb/1311867175.794862.png 1311867175.788225 depth/1311867175.788225.png
1311867175.828797 rgb/1311867175.828797.png 1311867175.822546 depth/1311867175.822546.png
1311867175.862552 rgb/1311867175.862552.png 1311867175.852791 depth/1311867175.852791.png
1311867175.894608 rgb/1311867175.894608.png 1311867175.888452 depth/1311867175.888452.png
1311867175.928243 rgb/1311867175.928243.png 1311867175.922221 depth/1311867175.922221.png
1311867175.962937 rgb/1311867175.962937.png 1311867175.956655 depth/1311867175.956655.png
1311867175.998300 rgb/1311867175.998300.png 1311867175.988251 depth/1311867175.988251.png
1311867176.026851 rgb/1311867176.026851.png 1311867176.022409 depth/1311867176.022409.png
1311867176.062706 rgb/1311867176.062706.png 1311867176.057742 depth/1311867176.057742.png
1311867176.094660 rgb/1311867176.094660.png 1311867176.089212 depth/1311867176.089212.png
1311867176.126812 rgb/1311867176.126812.png 1311867176.123317 depth/1311867176.123317.png
1311867176.162590 rgb/1311867176.162590.png 1311867176.156464 depth/1311867176.156464.png
1311867176.194692 rgb/1311867176.194692.png 1311867176.188489 depth/1311867176.188489.png
1311867176.226536 rgb/1311867176.226536.png 1311867176.220801 depth/1311867176.220801.png
1311867176.262502 rgb/1311867176.262502.png 1311867176.256432 depth/1311867176.256432.png
1311867176.294611 rgb/1311867176.294611.png 1311867176.289298 depth/1311867176.289298.png
1311867176.326602 rgb/1311867176.326602.png 1311867176.320323 depth/1311867176.320323.png
1311867176.362456 rgb/1311867176.362456.png 1311867176.356783 depth/1311867176.356783.png
1311867176.395244 rgb/1311867176.395244.png 1311867176.389335 depth/1311867176.389335.png
1311867176.426836 rgb/1311867176.426836.png 1311867176.421363 depth/1311867176.421363.png
1311867176.462966 rgb/1311867176.462966.png 1311867176.456687 depth/1311867176.456687.png
1311867176.494581 rgb/1311867176.494581.png 1311867176.488951 depth/1311867176.488951.png
1311867176.526621 rgb/1311867176.526621.png 1311867176.521537 depth/1311867176.521537.png
1311867176.563639 rgb/1311867176.563639.png 1311867176.558631 depth/1311867176.558631.png
1311867176.594609 rgb/1311867176.594609.png 1311867176.593559 depth/1311867176.593559.png
1311867176.628384 rgb/1311867176.628384.png 1311867176.621080 depth/1311867176.621080.png
1311867176.662578 rgb/1311867176.662578.png 1311867176.660404 depth/1311867176.660404.png
1311867176.694518 rgb/1311867176.694518.png 1311867176.689453 depth/1311867176.689453.png
1311867176.726589 rgb/1311867176.726589.png 1311867176.724143 depth/1311867176.724143.png
1311867176.763233 rgb/1311867176.763233.png 1311867176.758500 depth/1311867176.758500.png
1311867176.794768 rgb/1311867176.794768.png 1311867176.790063 depth/1311867176.790063.png
1311867176.826677 rgb/1311867176.826677.png 1311867176.820696 depth/1311867176.820696.png
1311867176.862731 rgb/1311867176.862731.png 1311867176.858590 depth/1311867176.858590.png
1311867176.894955 rgb/1311867176.894955.png 1311867176.890342 depth/1311867176.890342.png
1311867176.926818 rgb/1311867176.926818.png 1311867176.922599 depth/1311867176.922599.png
1311867176.965061 rgb/1311867176.965061.png 1311867176.960668 depth/1311867176.960668.png
1311867176.994748 rgb/1311867176.994748.png 1311867176.989703 depth/1311867176.989703.png
1311867177.026728 rgb/1311867177.026728.png 1311867177.020601 depth/1311867177.020601.png
1311867177.062634 rgb/1311867177.062634.png 1311867177.056330 depth/1311867177.056330.png
1311867177.094685 rgb/1311867177.094685.png 1311867177.090969 depth/1311867177.090969.png
1311867177.126615 rgb/1311867177.126615.png 1311867177.122005 depth/1311867177.122005.png
1311867177.162730 rgb/1311867177.162730.png 1311867177.157538 depth/1311867177.157538.png
1311867177.194646 rgb/1311867177.194646.png 1311867177.188556 depth/1311867177.188556.png
1311867177.226473 rgb/1311867177.226473.png 1311867177.226035 depth/1311867177.226035.png
1311867177.263864 rgb/1311867177.263864.png 1311867177.258123 depth/1311867177.258123.png
1311867177.294618 rgb/1311867177.294618.png 1311867177.289343 depth/1311867177.289343.png
1311867177.327609 rgb/1311867177.327609.png 1311867177.324415 depth/1311867177.324415.png
1311867177.362771 rgb/1311867177.362771.png 1311867177.356930 depth/1311867177.356930.png
1311867177.394609 rgb/1311867177.394609.png 1311867177.389075 depth/1311867177.389075.png
1311867177.426748 rgb/1311867177.426748.png 1311867177.431286 depth/1311867177.431286.png
1311867177.462604 rgb/1311867177.462604.png 1311867177.458323 depth/1311867177.458323.png
1311867177.494643 rgb/1311867177.494643.png 1311867177.489115 depth/1311867177.489115.png
1311867177.527617 rgb/1311867177.527617.png 1311867177.527632 depth/1311867177.527632.png
1311867177.562640 rgb/1311867177.562640.png 1311867177.556823 depth/1311867177.556823.png
1311867177.594731 rgb/1311867177.594731.png 1311867177.588870 depth/1311867177.588870.png
1311867177.631145 rgb/1311867177.631145.png 1311867177.624638 depth/1311867177.624638.png
1311867177.662483 rgb/1311867177.662483.png 1311867177.656627 depth/1311867177.656627.png
1311867177.694561 rgb/1311867177.694561.png 1311867177.688761 depth/1311867177.688761.png
1311867177.730584 rgb/1311867177.730584.png 1311867177.724609 depth/1311867177.724609.png
1311867177.762538 rgb/1311867177.762538.png 1311867177.756593 depth/1311867177.756593.png
1311867177.794559 rgb/1311867177.794559.png 1311867177.788810 depth/1311867177.788810.png
1311867177.830915 rgb/1311867177.830915.png 1311867177.827577 depth/1311867177.827577.png
1311867177.862532 rgb/1311867177.862532.png 1311867177.856268 depth/1311867177.856268.png
1311867177.894692 rgb/1311867177.894692.png 1311867177.888928 depth/1311867177.888928.png
1311867177.931786 rgb/1311867177.931786.png 1311867177.926179 depth/1311867177.926179.png
1311867177.962791 rgb/1311867177.962791.png 1311867177.956891 depth/1311867177.956891.png
1311867177.994777 rgb/1311867177.994777.png 1311867177.989128 depth/1311867177.989128.png
1311867178.030610 rgb/1311867178.030610.png 1311867178.025481 depth/1311867178.025481.png
1311867178.063448 rgb/1311867178.063448.png 1311867178.058077 depth/1311867178.058077.png
1311867178.095114 rgb/1311867178.095114.png 1311867178.089617 depth/1311867178.089617.png
1311867178.130791 rgb/1311867178.130791.png 1311867178.127721 depth/1311867178.127721.png
1311867178.162747 rgb/1311867178.162747.png 1311867178.157550 depth/1311867178.157550.png
1311867178.195046 rgb/1311867178.195046.png 1311867178.192727 depth/1311867178.192727.png
1311867178.230719 rgb/1311867178.230719.png 1311867178.224296 depth/1311867178.224296.png
1311867178.262894 rgb/1311867178.262894.png 1311867178.256639 depth/1311867178.256639.png
1311867178.295490 rgb/1311867178.295490.png 1311867178.288842 depth/1311867178.288842.png
1311867178.330667 rgb/1311867178.330667.png 1311867178.324664 depth/1311867178.324664.png
1311867178.362723 rgb/1311867178.362723.png 1311867178.360490 depth/1311867178.360490.png
1311867178.394944 rgb/1311867178.394944.png 1311867178.388795 depth/1311867178.388795.png
1311867178.430658 rgb/1311867178.430658.png 1311867178.427504 depth/1311867178.427504.png
1311867178.462874 rgb/1311867178.462874.png 1311867178.456833 depth/1311867178.456833.png
1311867178.494644 rgb/1311867178.494644.png 1311867178.493591 depth/1311867178.493591.png
1311867178.530627 rgb/1311867178.530627.png 1311867178.524720 depth/1311867178.524720.png
1311867178.562642 rgb/1311867178.562642.png 1311867178.556910 depth/1311867178.556910.png
1311867178.594700 rgb/1311867178.594700.png 1311867178.593205 depth/1311867178.593205.png
1311867178.630690 rgb/1311867178.630690.png 1311867178.627593 depth/1311867178.627593.png
1311867178.662641 rgb/1311867178.662641.png 1311867178.660756 depth/1311867178.660756.png
1311867178.694612 rgb/1311867178.694612.png 1311867178.693715 depth/1311867178.693715.png
1311867178.730745 rgb/1311867178.730745.png 1311867178.724521 depth/1311867178.724521.png
1311867178.763235 rgb/1311867178.763235.png 1311867178.757396 depth/1311867178.757396.png
1311867178.800680 rgb/1311867178.800680.png 1311867178.799313 depth/1311867178.799313.png
1311867178.830950 rgb/1311867178.830950.png 1311867178.824972 depth/1311867178.824972.png
1311867178.862794 rgb/1311867178.862794.png 1311867178.857434 depth/1311867178.857434.png
1311867178.895017 rgb/1311867178.895017.png 1311867178.895228 depth/1311867178.895228.png
1311867178.930621 rgb/1311867178.930621.png 1311867178.925076 depth/1311867178.925076.png
1311867178.962761 rgb/1311867178.962761.png 1311867178.958688 depth/1311867178.958688.png
1311867178.994683 rgb/1311867178.994683.png 1311867178.993422 depth/1311867178.993422.png
1311867179.030916 rgb/1311867179.030916.png 1311867179.026970 depth/1311867179.026970.png
1311867179.062812 rgb/1311867179.062812.png 1311867179.057601 depth/1311867179.057601.png
1311867179.096812 rgb/1311867179.096812.png 1311867179.096820 depth/1311867179.096820.png
1311867179.131037 rgb/1311867179.131037.png 1311867179.124823 depth/1311867179.124823.png
1311867179.162754 rgb/1311867179.162754.png 1311867179.156587 depth/1311867179.156587.png
1311867179.195685 rgb/1311867179.195685.png 1311867179.195701 depth/1311867179.195701.png
1311867179.230747 rgb/1311867179.230747.png 1311867179.224644 depth/1311867179.224644.png
1311867179.263461 rgb/1311867179.263461.png 1311867179.257244 depth/1311867179.257244.png
1311867179.295920 rgb/1311867179.295920.png 1311867179.295933 depth/1311867179.295933.png
1311867179.330715 rgb/1311867179.330715.png 1311867179.327496 depth/1311867179.327496.png
1311867179.362930 rgb/1311867179.362930.png 1311867179.356659 depth/1311867179.356659.png
1311867179.394849 rgb/1311867179.394849.png 1311867179.393013 depth/1311867179.393013.png
1311867179.430804 rgb/1311867179.430804.png 1311867179.428452 depth/1311867179.428452.png
1311867179.463746 rgb/1311867179.463746.png 1311867179.458555 depth/1311867179.458555.png
1311867179.494947 rgb/1311867179.494947.png 1311867179.492659 depth/1311867179.492659.png
1311867179.530780 rgb/1311867179.530780.png 1311867179.524514 depth/1311867179.524514.png
1311867179.562761 rgb/1311867179.562761.png 1311867179.556366 depth/1311867179.556366.png
1311867179.594674 rgb/1311867179.594674.png 1311867179.593206 depth/1311867179.593206.png
1311867179.630690 rgb/1311867179.630690.png 1311867179.624449 depth/1311867179.624449.png
1311867179.662575 rgb/1311867179.662575.png 1311867179.661662 depth/1311867179.661662.png
1311867179.694605 rgb/1311867179.694605.png 1311867179.694458 depth/1311867179.694458.png
1311867179.730947 rgb/1311867179.730947.png 1311867179.724734 depth/1311867179.724734.png
1311867179.762727 rgb/1311867179.762727.png 1311867179.761284 depth/1311867179.761284.png
1311867179.794891 rgb/1311867179.794891.png 1311867179.792803 depth/1311867179.792803.png
1311867179.830753 rgb/1311867179.830753.png 1311867179.824885 depth/1311867179.824885.png
1311867179.862798 rgb/1311867179.862798.png 1311867179.861218 depth/1311867179.861218.png
1311867179.894804 rgb/1311867179.894804.png 1311867179.892712 depth/1311867179.892712.png
1311867179.930905 rgb/1311867179.930905.png 1311867179.924723 depth/1311867179.924723.png
1311867179.963493 rgb/1311867179.963493.png 1311867179.963538 depth/1311867179.963538.png
1311867179.995888 rgb/1311867179.995888.png 1311867179.992996 depth/1311867179.992996.png
1311867180.030977 rgb/1311867180.030977.png 1311867180.026152 depth/1311867180.026152.png
1311867180.062647 rgb/1311867180.062647.png 1311867180.060614 depth/1311867180.060614.png
1311867180.094773 rgb/1311867180.094773.png 1311867180.092930 depth/1311867180.092930.png
1311867180.130773 rgb/1311867180.130773.png 1311867180.125768 depth/1311867180.125768.png
1311867180.163680 rgb/1311867180.163680.png 1311867180.163690 depth/1311867180.163690.png
1311867180.194909 rgb/1311867180.194909.png 1311867180.192644 depth/1311867180.192644.png
1311867180.230814 rgb/1311867180.230814.png 1311867180.224846 depth/1311867180.224846.png
1311867180.263762 rgb/1311867180.263762.png 1311867180.261752 depth/1311867180.261752.png
1311867180.294755 rgb/1311867180.294755.png 1311867180.293896 depth/1311867180.293896.png
1311867180.330867 rgb/1311867180.330867.png 1311867180.327074 depth/1311867180.327074.png
1311867180.365820 rgb/1311867180.365820.png 1311867180.365829 depth/1311867180.365829.png
1311867180.396166 rgb/1311867180.396166.png 1311867180.396411 depth/1311867180.396411.png
1311867180.430915 rgb/1311867180.430915.png 1311867180.427854 depth/1311867180.427854.png
1311867180.467067 rgb/1311867180.467067.png 1311867180.461765 depth/1311867180.461765.png
1311867180.494756 rgb/1311867180.494756.png 1311867180.493086 depth/1311867180.493086.png
1311867180.530888 rgb/1311867180.530888.png 1311867180.525941 depth/1311867180.525941.png
1311867180.562951 rgb/1311867180.562951.png 1311867180.560710 depth/1311867180.560710.png
1311867180.594691 rgb/1311867180.594691.png 1311867180.593978 depth/1311867180.593978.png
1311867180.630813 rgb/1311867180.630813.png 1311867180.627066 depth/1311867180.627066.png
1311867180.664091 rgb/1311867180.664091.png 1311867180.661734 depth/1311867180.661734.png
1311867180.695760 rgb/1311867180.695760.png 1311867180.695786 depth/1311867180.695786.png
1311867180.730974 rgb/1311867180.730974.png 1311867180.724682 depth/1311867180.724682.png
1311867180.765038 rgb/1311867180.765038.png 1311867180.765083 depth/1311867180.765083.png
1311867180.794928 rgb/1311867180.794928.png 1311867180.793675 depth/1311867180.793675.png
1311867180.830924 rgb/1311867180.830924.png 1311867180.828968 depth/1311867180.828968.png
1311867180.865254 rgb/1311867180.865254.png 1311867180.865270 depth/1311867180.865270.png
1311867180.896647 rgb/1311867180.896647.png 1311867180.896192 depth/1311867180.896192.png
1311867180.930605 rgb/1311867180.930605.png 1311867180.929785 depth/1311867180.929785.png
1311867180.963183 rgb/1311867180.963183.png 1311867180.962601 depth/1311867180.962601.png
1311867180.994818 rgb/1311867180.994818.png 1311867180.992656 depth/1311867180.992656.png
1311867181.030831 rgb/1311867181.030831.png 1311867181.030155 depth/1311867181.030155.png
1311867181.062783 rgb/1311867181.062783.png 1311867181.062610 depth/1311867181.062610.png
1311867181.094872 rgb/1311867181.094872.png 1311867181.093163 depth/1311867181.093163.png
1311867181.131191 rgb/1311867181.131191.png 1311867181.128759 depth/1311867181.128759.png
1311867181.162904 rgb/1311867181.162904.png 1311867181.162953 depth/1311867181.162953.png
1311867181.197251 rgb/1311867181.197251.png 1311867181.197283 depth/1311867181.197283.png
1311867181.234246 rgb/1311867181.234246.png 1311867181.231080 depth/1311867181.231080.png
1311867181.262936 rgb/1311867181.262936.png 1311867181.262009 depth/1311867181.262009.png
1311867181.294809 rgb/1311867181.294809.png 1311867181.294030 depth/1311867181.294030.png
1311867181.331699 rgb/1311867181.331699.png 1311867181.331714 depth/1311867181.331714.png
1311867181.362671 rgb/1311867181.362671.png 1311867181.362187 depth/1311867181.362187.png
1311867181.394822 rgb/1311867181.394822.png 1311867181.393741 depth/1311867181.393741.png
1311867181.430895 rgb/1311867181.430895.png 1311867181.429039 depth/1311867181.429039.png
1311867181.462831 rgb/1311867181.462831.png 1311867181.461533 depth/1311867181.461533.png
1311867181.496340 rgb/1311867181.496340.png 1311867181.496361 depth/1311867181.496361.png
1311867181.535911 rgb/1311867181.535911.png 1311867181.530602 depth/1311867181.530602.png
1311867181.563214 rgb/1311867181.563214.png 1311867181.567172 depth/1311867181.567172.png
1311867181.594861 rgb/1311867181.594861.png 1311867181.594580 depth/1311867181.594580.png
1311867181.630984 rgb/1311867181.630984.png 1311867181.631359 depth/1311867181.631359.png
1311867181.662857 rgb/1311867181.662857.png 1311867181.660906 depth/1311867181.660906.png
1311867181.694923 rgb/1311867181.694923.png 1311867181.692771 depth/1311867181.692771.png
1311867181.731083 rgb/1311867181.731083.png 1311867181.730273 depth/1311867181.730273.png
1311867181.763477 rgb/1311867181.763477.png 1311867181.763484 depth/1311867181.763484.png
1311867181.794898 rgb/1311867181.794898.png 1311867181.792947 depth/1311867181.792947.png
1311867181.830801 rgb/1311867181.830801.png 1311867181.828757 depth/1311867181.828757.png
1311867181.862798 rgb/1311867181.862798.png 1311867181.862225 depth/1311867181.862225.png
1311867181.894929 rgb/1311867181.894929.png 1311867181.892924 depth/1311867181.892924.png
1311867181.930799 rgb/1311867181.930799.png 1311867181.929356 depth/1311867181.929356.png
1311867181.962919 rgb/1311867181.962919.png 1311867181.960985 depth/1311867181.960985.png
1311867181.995551 rgb/1311867181.995551.png 1311867181.995560 depth/1311867181.995560.png
1311867182.031939 rgb/1311867182.031939.png 1311867182.032064 depth/1311867182.032064.png
1311867182.062900 rgb/1311867182.062900.png 1311867182.060982 depth/1311867182.060982.png
1311867182.094884 rgb/1311867182.094884.png 1311867182.093419 depth/1311867182.093419.png
1311867182.131453 rgb/1311867182.131453.png 1311867182.131484 depth/1311867182.131484.png
1311867182.162992 rgb/1311867182.162992.png 1311867182.160935 depth/1311867182.160935.png
1311867182.199442 rgb/1311867182.199442.png 1311867182.199450 depth/1311867182.199450.png
1311867182.230774 rgb/1311867182.230774.png 1311867182.229453 depth/1311867182.229453.png
1311867182.262912 rgb/1311867182.262912.png 1311867182.261573 depth/1311867182.261573.png
1311867182.297304 rgb/1311867182.297304.png 1311867182.297354 depth/1311867182.297354.png
1311867182.330846 rgb/1311867182.330846.png 1311867182.328882 depth/1311867182.328882.png
1311867182.362967 rgb/1311867182.362967.png 1311867182.360555 depth/1311867182.360555.png
1311867182.399028 rgb/1311867182.399028.png 1311867182.399037 depth/1311867182.399037.png
1311867182.430812 rgb/1311867182.430812.png 1311867182.428810 depth/1311867182.428810.png
1311867182.462944 rgb/1311867182.462944.png 1311867182.460845 depth/1311867182.460845.png
1311867182.496953 rgb/1311867182.496953.png 1311867182.496960 depth/1311867182.496960.png
1311867182.530950 rgb/1311867182.530950.png 1311867182.528654 depth/1311867182.528654.png
1311867182.562970 rgb/1311867182.562970.png 1311867182.561034 depth/1311867182.561034.png
1311867182.603637 rgb/1311867182.603637.png 1311867182.600491 depth/1311867182.600491.png
1311867182.630845 rgb/1311867182.630845.png 1311867182.630737 depth/1311867182.630737.png
1311867182.663572 rgb/1311867182.663572.png 1311867182.663592 depth/1311867182.663592.png
1311867182.696991 rgb/1311867182.696991.png 1311867182.697002 depth/1311867182.697002.png
1311867182.733050 rgb/1311867182.733050.png 1311867182.733064 depth/1311867182.733064.png
1311867182.763107 rgb/1311867182.763107.png 1311867182.763113 depth/1311867182.763113.png
1311867182.797044 rgb/1311867182.797044.png 1311867182.797055 depth/1311867182.797055.png
1311867182.830690 rgb/1311867182.830690.png 1311867182.830699 depth/1311867182.830699.png
1311867182.864091 rgb/1311867182.864091.png 1311867182.864117 depth/1311867182.864117.png
1311867182.896985 rgb/1311867182.896985.png 1311867182.896997 depth/1311867182.896997.png
1311867182.931887 rgb/1311867182.931887.png 1311867182.931899 depth/1311867182.931899.png
1311867182.963056 rgb/1311867182.963056.png 1311867182.963072 depth/1311867182.963072.png
1311867182.998350 rgb/1311867182.998350.png 1311867182.998395 depth/1311867182.998395.png
1311867183.030883 rgb/1311867183.030883.png 1311867183.029566 depth/1311867183.029566.png
1311867183.062860 rgb/1311867183.062860.png 1311867183.061472 depth/1311867183.061472.png
1311867183.100040 rgb/1311867183.100040.png 1311867183.100050 depth/1311867183.100050.png
1311867183.134468 rgb/1311867183.134468.png 1311867183.134478 depth/1311867183.134478.png
1311867183.167324 rgb/1311867183.167324.png 1311867183.161718 depth/1311867183.161718.png
1311867183.200473 rgb/1311867183.200473.png 1311867183.200492 depth/1311867183.200492.png
1311867183.231128 rgb/1311867183.231128.png 1311867183.230460 depth/1311867183.230460.png
1311867183.263324 rgb/1311867183.263324.png 1311867183.263335 depth/1311867183.263335.png
1311867183.299097 rgb/1311867183.299097.png 1311867183.299110 depth/1311867183.299110.png
1311867183.332092 rgb/1311867183.332092.png 1311867183.329084 depth/1311867183.329084.png
1311867183.369524 rgb/1311867183.369524.png 1311867183.368481 depth/1311867183.368481.png
1311867183.398546 rgb/1311867183.398546.png 1311867183.398621 depth/1311867183.398621.png
1311867183.431155 rgb/1311867183.431155.png 1311867183.430378 depth/1311867183.430378.png
1311867183.466738 rgb/1311867183.466738.png 1311867183.466745 depth/1311867183.466745.png
1311867183.498828 rgb/1311867183.498828.png 1311867183.498834 depth/1311867183.498834.png
1311867183.532172 rgb/1311867183.532172.png 1311867183.532183 depth/1311867183.532183.png
1311867183.566151 rgb/1311867183.566151.png 1311867183.566161 depth/1311867183.566161.png
1311867183.598535 rgb/1311867183.598535.png 1311867183.598548 depth/1311867183.598548.png
1311867183.631088 rgb/1311867183.631088.png 1311867183.629509 depth/1311867183.629509.png
1311867183.664879 rgb/1311867183.664879.png 1311867183.664926 depth/1311867183.664926.png
1311867183.699353 rgb/1311867183.699353.png 1311867183.699395 depth/1311867183.699395.png
1311867183.730893 rgb/1311867183.730893.png 1311867183.729812 depth/1311867183.729812.png
1311867183.767624 rgb/1311867183.767624.png 1311867183.767648 depth/1311867183.767648.png
1311867183.797176 rgb/1311867183.797176.png 1311867183.797187 depth/1311867183.797187.png
1311867183.830907 rgb/1311867183.830907.png 1311867183.829710 depth/1311867183.829710.png
1311867183.865499 rgb/1311867183.865499.png 1311867183.865505 depth/1311867183.865505.png
1311867183.897086 rgb/1311867183.897086.png 1311867183.897097 depth/1311867183.897097.png
1311867183.931483 rgb/1311867183.931483.png 1311867183.931494 depth/1311867183.931494.png
1311867183.965821 rgb/1311867183.965821.png 1311867183.965832 depth/1311867183.965832.png
1311867183.996668 rgb/1311867183.996668.png 1311867183.996678 depth/1311867183.996678.png
1311867184.030969 rgb/1311867184.030969.png 1311867184.030585 depth/1311867184.030585.png
1311867184.064723 rgb/1311867184.064723.png 1311867184.064785 depth/1311867184.064785.png
1311867184.096811 rgb/1311867184.096811.png 1311867184.096889 depth/1311867184.096889.png
1311867184.131226 rgb/1311867184.131226.png 1311867184.129342 depth/1311867184.129342.png
1311867184.165054 rgb/1311867184.165054.png 1311867184.165064 depth/1311867184.165064.png
1311867184.196946 rgb/1311867184.196946.png 1311867184.196956 depth/1311867184.196956.png
1311867184.230936 rgb/1311867184.230936.png 1311867184.228912 depth/1311867184.228912.png
1311867184.268102 rgb/1311867184.268102.png 1311867184.268137 depth/1311867184.268137.png
1311867184.298370 rgb/1311867184.298370.png 1311867184.298390 depth/1311867184.298390.png
1311867184.331470 rgb/1311867184.331470.png 1311867184.329391 depth/1311867184.329391.png
1311867184.369763 rgb/1311867184.369763.png 1311867184.369784 depth/1311867184.369784.png
1311867184.400006 rgb/1311867184.400006.png 1311867184.400022 depth/1311867184.400022.png
1311867184.431061 rgb/1311867184.431061.png 1311867184.429210 depth/1311867184.429210.png
1311867184.465574 rgb/1311867184.465574.png 1311867184.465581 depth/1311867184.465581.png
1311867184.503767 rgb/1311867184.503767.png 1311867184.503424 depth/1311867184.503424.png
1311867184.531088 rgb/1311867184.531088.png 1311867184.529928 depth/1311867184.529928.png
1311867184.568280 rgb/1311867184.568280.png 1311867184.568293 depth/1311867184.568293.png
1311867184.597993 rgb/1311867184.597993.png 1311867184.601807 depth/1311867184.601807.png
1311867184.635545 rgb/1311867184.635545.png 1311867184.636740 depth/1311867184.636740.png
1311867184.666244 rgb/1311867184.666244.png 1311867184.665906 depth/1311867184.665906.png
1311867184.699477 rgb/1311867184.699477.png 1311867184.699493 depth/1311867184.699493.png
1311867184.735909 rgb/1311867184.735909.png 1311867184.735916 depth/1311867184.735916.png
1311867184.769022 rgb/1311867184.769022.png 1311867184.769069 depth/1311867184.769069.png
1311867184.799534 rgb/1311867184.799534.png 1311867184.800128 depth/1311867184.800128.png
1311867184.834825 rgb/1311867184.834825.png 1311867184.834844 depth/1311867184.834844.png
1311867184.868574 rgb/1311867184.868574.png 1311867184.869066 depth/1311867184.869066.png
1311867184.905521 rgb/1311867184.905521.png 1311867184.900567 depth/1311867184.900567.png
1311867184.933218 rgb/1311867184.933218.png 1311867184.933228 depth/1311867184.933228.png
1311867184.965627 rgb/1311867184.965627.png 1311867184.965641 depth/1311867184.965641.png
1311867184.998315 rgb/1311867184.998315.png 1311867184.998325 depth/1311867184.998325.png
1311867185.036045 rgb/1311867185.036045.png 1311867185.036055 depth/1311867185.036055.png
1311867185.065223 rgb/1311867185.065223.png 1311867185.065235 depth/1311867185.065235.png
1311867185.099109 rgb/1311867185.099109.png 1311867185.099128 depth/1311867185.099128.png
1311867185.136065 rgb/1311867185.136065.png 1311867185.136078 depth/1311867185.136078.png
1311867185.164814 rgb/1311867185.164814.png 1311867185.164871 depth/1311867185.164871.png
1311867185.200008 rgb/1311867185.200008.png 1311867185.200072 depth/1311867185.200072.png
1311867185.234264 rgb/1311867185.234264.png 1311867185.234292 depth/1311867185.234292.png
1311867185.266332 rgb/1311867185.266332.png 1311867185.266395 depth/1311867185.266395.png
1311867185.297013 rgb/1311867185.297013.png 1311867185.297055 depth/1311867185.297055.png
1311867185.335984 rgb/1311867185.335984.png 1311867185.336014 depth/1311867185.336014.png
1311867185.368164 rgb/1311867185.368164.png 1311867185.368178 depth/1311867185.368178.png
1311867185.403637 rgb/1311867185.403637.png 1311867185.403651 depth/1311867185.403651.png
1311867185.437322 rgb/1311867185.437322.png 1311867185.438639 depth/1311867185.438639.png
1311867185.465497 rgb/1311867185.465497.png 1311867185.465545 depth/1311867185.465545.png
1311867185.500623 rgb/1311867185.500623.png 1311867185.501391 depth/1311867185.501391.png
1311867185.533624 rgb/1311867185.533624.png 1311867185.533633 depth/1311867185.533633.png
1311867185.566669 rgb/1311867185.566669.png 1311867185.566680 depth/1311867185.566680.png
1311867185.596975 rgb/1311867185.596975.png 1311867185.597054 depth/1311867185.597054.png
1311867185.632940 rgb/1311867185.632940.png 1311867185.632947 depth/1311867185.632947.png
1311867185.666408 rgb/1311867185.666408.png 1311867185.666418 depth/1311867185.666418.png
1311867185.697332 rgb/1311867185.697332.png 1311867185.697339 depth/1311867185.697339.png
1311867185.735179 rgb/1311867185.735179.png 1311867185.735190 depth/1311867185.735190.png
1311867185.764971 rgb/1311867185.764971.png 1311867185.764977 depth/1311867185.764977.png
1311867185.798952 rgb/1311867185.798952.png 1311867185.798965 depth/1311867185.798965.png
1311867185.832792 rgb/1311867185.832792.png 1311867185.832800 depth/1311867185.832800.png
1311867185.864904 rgb/1311867185.864904.png 1311867185.864910 depth/1311867185.864910.png
1311867185.895173 rgb/1311867185.895173.png 1311867185.903042 depth/1311867185.903042.png
1311867185.935978 rgb/1311867185.935978.png 1311867185.939679 depth/1311867185.939679.png
1311867185.965051 rgb/1311867185.965051.png 1311867185.965061 depth/1311867185.965061.png
1311867185.995231 rgb/1311867185.995231.png 1311867186.003947 depth/1311867186.003947.png
1311867186.035964 rgb/1311867186.035964.png 1311867186.039692 depth/1311867186.039692.png
1311867186.065305 rgb/1311867186.065305.png 1311867186.065324 depth/1311867186.065324.png
1311867186.095284 rgb/1311867186.095284.png 1311867186.104734 depth/1311867186.104734.png
1311867186.136102 rgb/1311867186.136102.png 1311867186.136118 depth/1311867186.136118.png
1311867186.164936 rgb/1311867186.164936.png 1311867186.164945 depth/1311867186.164945.png
1311867186.195188 rgb/1311867186.195188.png 1311867186.204475 depth/1311867186.204475.png
1311867186.235893 rgb/1311867186.235893.png 1311867186.235966 depth/1311867186.235966.png
1311867186.267490 rgb/1311867186.267490.png 1311867186.267308 depth/1311867186.267308.png
1311867186.295199 rgb/1311867186.295199.png 1311867186.303084 depth/1311867186.303084.png
1311867186.334915 rgb/1311867186.334915.png 1311867186.334927 depth/1311867186.334927.png
1311867186.366964 rgb/1311867186.366964.png 1311867186.367016 depth/1311867186.367016.png
1311867186.395131 rgb/1311867186.395131.png 1311867186.401985 depth/1311867186.401985.png
1311867186.436010 rgb/1311867186.436010.png 1311867186.436021 depth/1311867186.436021.png
1311867186.465948 rgb/1311867186.465948.png 1311867186.465889 depth/1311867186.465889.png
1311867186.495214 rgb/1311867186.495214.png 1311867186.503114 depth/1311867186.503114.png
1311867186.536274 rgb/1311867186.536274.png 1311867186.536317 depth/1311867186.536317.png
1311867186.565107 rgb/1311867186.565107.png 1311867186.565113 depth/1311867186.565113.png
1311867186.595160 rgb/1311867186.595160.png 1311867186.601422 depth/1311867186.601422.png
1311867186.636236 rgb/1311867186.636236.png 1311867186.636263 depth/1311867186.636263.png
1311867186.665014 rgb/1311867186.665014.png 1311867186.665048 depth/1311867186.665048.png
1311867186.704365 rgb/1311867186.704365.png 1311867186.704381 depth/1311867186.704381.png
1311867186.733752 rgb/1311867186.733752.png 1311867186.733775 depth/1311867186.733775.png
1311867186.767288 rgb/1311867186.767288.png 1311867186.767318 depth/1311867186.767318.png
1311867186.804720 rgb/1311867186.804720.png 1311867186.804730 depth/1311867186.804730.png
1311867186.834068 rgb/1311867186.834068.png 1311867186.834075 depth/1311867186.834075.png
1311867186.869100 rgb/1311867186.869100.png 1311867186.877600 depth/1311867186.877600.png
1311867186.905187 rgb/1311867186.905187.png 1311867186.905210 depth/1311867186.905210.png
1311867186.933418 rgb/1311867186.933418.png 1311867186.933424 depth/1311867186.933424.png
1311867186.965693 rgb/1311867186.965693.png 1311867186.966338 depth/1311867186.966338.png
1311867187.001705 rgb/1311867187.001705.png 1311867187.001714 depth/1311867187.001714.png
1311867187.033640 rgb/1311867187.033640.png 1311867187.033646 depth/1311867187.033646.png
1311867187.063280 rgb/1311867187.063280.png 1311867187.074935 depth/1311867187.074935.png
1311867187.101595 rgb/1311867187.101595.png 1311867187.101603 depth/1311867187.101603.png
1311867187.133979 rgb/1311867187.133979.png 1311867187.134207 depth/1311867187.134207.png
1311867187.163262 rgb/1311867187.163262.png 1311867187.171021 depth/1311867187.171021.png
1311867187.204123 rgb/1311867187.204123.png 1311867187.204137 depth/1311867187.204137.png
1311867187.233159 rgb/1311867187.233159.png 1311867187.233166 depth/1311867187.233166.png
1311867187.263350 rgb/1311867187.263350.png 1311867187.270763 depth/1311867187.270763.png
1311867187.301486 rgb/1311867187.301486.png 1311867187.301506 depth/1311867187.301506.png
1311867187.333649 rgb/1311867187.333649.png 1311867187.333657 depth/1311867187.333657.png
1311867187.363171 rgb/1311867187.363171.png 1311867187.370759 depth/1311867187.370759.png
1311867187.403345 rgb/1311867187.403345.png 1311867187.403353 depth/1311867187.403353.png
1311867187.433580 rgb/1311867187.433580.png 1311867187.433590 depth/1311867187.433590.png
1311867187.463190 rgb/1311867187.463190.png 1311867187.476316 depth/1311867187.476316.png
1311867187.505626 rgb/1311867187.505626.png 1311867187.505640 depth/1311867187.505640.png
1311867187.534189 rgb/1311867187.534189.png 1311867187.534219 depth/1311867187.534219.png
1311867187.563217 rgb/1311867187.563217.png 1311867187.570968 depth/1311867187.570968.png
1311867187.604561 rgb/1311867187.604561.png 1311867187.604579 depth/1311867187.604579.png
1311867187.635392 rgb/1311867187.635392.png 1311867187.633614 depth/1311867187.633614.png
1311867187.663270 rgb/1311867187.663270.png 1311867187.670769 depth/1311867187.670769.png
1311867187.703564 rgb/1311867187.703564.png 1311867187.703577 depth/1311867187.703577.png
1311867187.734539 rgb/1311867187.734539.png 1311867187.734548 depth/1311867187.734548.png
1311867187.763190 rgb/1311867187.763190.png 1311867187.770782 depth/1311867187.770782.png
1311867187.801705 rgb/1311867187.801705.png 1311867187.801751 depth/1311867187.801751.png
1311867187.833949 rgb/1311867187.833949.png 1311867187.833961 depth/1311867187.833961.png
1311867187.863411 rgb/1311867187.863411.png 1311867187.870809 depth/1311867187.870809.png
1311867187.903871 rgb/1311867187.903871.png 1311867187.903881 depth/1311867187.903881.png
1311867187.933221 rgb/1311867187.933221.png 1311867187.936300 depth/1311867187.936300.png
1311867187.963534 rgb/1311867187.963534.png 1311867187.971342 depth/1311867187.971342.png
1311867188.004742 rgb/1311867188.004742.png 1311867188.004757 depth/1311867188.004757.png
1311867188.033304 rgb/1311867188.033304.png 1311867188.033311 depth/1311867188.033311.png
1311867188.063418 rgb/1311867188.063418.png 1311867188.069870 depth/1311867188.069870.png
1311867188.108880 rgb/1311867188.108880.png 1311867188.104646 depth/1311867188.104646.png
1311867188.135990 rgb/1311867188.135990.png 1311867188.135997 depth/1311867188.135997.png
1311867188.163360 rgb/1311867188.163360.png 1311867188.170335 depth/1311867188.170335.png
1311867188.202654 rgb/1311867188.202654.png 1311867188.202672 depth/1311867188.202672.png
1311867188.235201 rgb/1311867188.235201.png 1311867188.235245 depth/1311867188.235245.png
1311867188.263272 rgb/1311867188.263272.png 1311867188.270646 depth/1311867188.270646.png
1311867188.304719 rgb/1311867188.304719.png 1311867188.304734 depth/1311867188.304734.png
1311867188.331453 rgb/1311867188.331453.png 1311867188.339880 depth/1311867188.339880.png
1311867188.363382 rgb/1311867188.363382.png 1311867188.371880 depth/1311867188.371880.png
1311867188.402043 rgb/1311867188.402043.png 1311867188.405447 depth/1311867188.405447.png
1311867188.431385 rgb/1311867188.431385.png 1311867188.439879 depth/1311867188.439879.png
1311867188.463247 rgb/1311867188.463247.png 1311867188.472450 depth/1311867188.472450.png
1311867188.504901 rgb/1311867188.504901.png 1311867188.504916 depth/1311867188.504916.png
1311867188.531435 rgb/1311867188.531435.png 1311867188.538999 depth/1311867188.538999.png
1311867188.563332 rgb/1311867188.563332.png 1311867188.572389 depth/1311867188.572389.png
1311867188.604580 rgb/1311867188.604580.png 1311867188.604596 depth/1311867188.604596.png
1311867188.631500 rgb/1311867188.631500.png 1311867188.639834 depth/1311867188.639834.png
1311867188.663337 rgb/1311867188.663337.png 1311867188.671508 depth/1311867188.671508.png
1311867188.703814 rgb/1311867188.703814.png 1311867188.703830 depth/1311867188.703830.png
1311867188.731585 rgb/1311867188.731585.png 1311867188.739383 depth/1311867188.739383.png
1311867188.763294 rgb/1311867188.763294.png 1311867188.772105 depth/1311867188.772105.png
1311867188.804516 rgb/1311867188.804516.png 1311867188.804522 depth/1311867188.804522.png
1311867188.831350 rgb/1311867188.831350.png 1311867188.840243 depth/1311867188.840243.png
1311867188.863544 rgb/1311867188.863544.png 1311867188.870599 depth/1311867188.870599.png
1311867188.901620 rgb/1311867188.901620.png 1311867188.901631 depth/1311867188.901631.png
1311867188.931465 rgb/1311867188.931465.png 1311867188.940177 depth/1311867188.940177.png
1311867188.963444 rgb/1311867188.963444.png 1311867188.970999 depth/1311867188.970999.png
1311867189.005216 rgb/1311867189.005216.png 1311867189.005226 depth/1311867189.005226.png
1311867189.031438 rgb/1311867189.031438.png 1311867189.040010 depth/1311867189.040010.png
1311867189.063539 rgb/1311867189.063539.png 1311867189.072433 depth/1311867189.072433.png
1311867189.102629 rgb/1311867189.102629.png 1311867189.102636 depth/1311867189.102636.png
1311867189.131312 rgb/1311867189.131312.png 1311867189.141764 depth/1311867189.141764.png
1311867189.163420 rgb/1311867189.163420.png 1311867189.171792 depth/1311867189.171792.png
1311867189.201890 rgb/1311867189.201890.png 1311867189.201907 depth/1311867189.201907.png
1311867189.231285 rgb/1311867189.231285.png 1311867189.239063 depth/1311867189.239063.png
1311867189.263345 rgb/1311867189.263345.png 1311867189.272264 depth/1311867189.272264.png
1311867189.304679 rgb/1311867189.304679.png 1311867189.304380 depth/1311867189.304380.png
1311867189.331405 rgb/1311867189.331405.png 1311867189.339797 depth/1311867189.339797.png
1311867189.363335 rgb/1311867189.363335.png 1311867189.372036 depth/1311867189.372036.png
1311867189.405684 rgb/1311867189.405684.png 1311867189.405695 depth/1311867189.405695.png
1311867189.431458 rgb/1311867189.431458.png 1311867189.440502 depth/1311867189.440502.png
1311867189.463454 rgb/1311867189.463454.png 1311867189.472913 depth/1311867189.472913.png
1311867189.505937 rgb/1311867189.505937.png 1311867189.506040 depth/1311867189.506040.png
1311867189.531417 rgb/1311867189.531417.png 1311867189.539429 depth/1311867189.539429.png
1311867189.563319 rgb/1311867189.563319.png 1311867189.572027 depth/1311867189.572027.png
1311867189.599369 rgb/1311867189.599369.png 1311867189.611291 depth/1311867189.611291.png
1311867189.631378 rgb/1311867189.631378.png 1311867189.642422 depth/1311867189.642422.png
1311867189.663469 rgb/1311867189.663469.png 1311867189.672840 depth/1311867189.672840.png
1311867189.699784 rgb/1311867189.699784.png 1311867189.706587 depth/1311867189.706587.png
1311867189.731458 rgb/1311867189.731458.png 1311867189.740172 depth/1311867189.740172.png
1311867189.763361 rgb/1311867189.763361.png 1311867189.772976 depth/1311867189.772976.png
1311867189.799486 rgb/1311867189.799486.png 1311867189.807397 depth/1311867189.807397.png
1311867189.831366 rgb/1311867189.831366.png 1311867189.840531 depth/1311867189.840531.png
1311867189.863410 rgb/1311867189.863410.png 1311867189.871353 depth/1311867189.871353.png
1311867189.899521 rgb/1311867189.899521.png 1311867189.910268 depth/1311867189.910268.png
1311867189.931364 rgb/1311867189.931364.png 1311867189.940226 depth/1311867189.940226.png
1311867189.963340 rgb/1311867189.963340.png 1311867189.972762 depth/1311867189.972762.png
1311867189.999434 rgb/1311867189.999434.png 1311867190.010701 depth/1311867190.010701.png
1311867190.031516 rgb/1311867190.031516.png 1311867190.040293 depth/1311867190.040293.png
1311867190.063454 rgb/1311867190.063454.png 1311867190.071904 depth/1311867190.071904.png
1311867190.099590 rgb/1311867190.099590.png 1311867190.109654 depth/1311867190.109654.png
1311867190.131422 rgb/1311867190.131422.png 1311867190.139637 depth/1311867190.139637.png
1311867190.163525 rgb/1311867190.163525.png 1311867190.170638 depth/1311867190.170638.png
1311867190.199492 rgb/1311867190.199492.png 1311867190.209602 depth/1311867190.209602.png
1311867190.231389 rgb/1311867190.231389.png 1311867190.239433 depth/1311867190.239433.png
1311867190.263381 rgb/1311867190.263381.png 1311867190.271481 depth/1311867190.271481.png
1311867190.299376 rgb/1311867190.299376.png 1311867190.307270 depth/1311867190.307270.png
1311867190.331359 rgb/1311867190.331359.png 1311867190.341473 depth/1311867190.341473.png
1311867190.363437 rgb/1311867190.363437.png 1311867190.371683 depth/1311867190.371683.png
1311867190.399467 rgb/1311867190.399467.png 1311867190.410109 depth/1311867190.410109.png
1311867190.431374 rgb/1311867190.431374.png 1311867190.439496 depth/1311867190.439496.png
1311867190.463341 rgb/1311867190.463341.png 1311867190.470820 depth/1311867190.470820.png
1311867190.499357 rgb/1311867190.499357.png 1311867190.509753 depth/1311867190.509753.png
1311867190.531809 rgb/1311867190.531809.png 1311867190.540519 depth/1311867190.540519.png
1311867190.563353 rgb/1311867190.563353.png 1311867190.570844 depth/1311867190.570844.png
1311867190.599451 rgb/1311867190.599451.png 1311867190.606775 depth/1311867190.606775.png
1311867190.631421 rgb/1311867190.631421.png 1311867190.638994 depth/1311867190.638994.png
1311867190.663424 rgb/1311867190.663424.png 1311867190.672366 depth/1311867190.672366.png
1311867190.699639 rgb/1311867190.699639.png 1311867190.711498 depth/1311867190.711498.png
1311867190.731381 rgb/1311867190.731381.png 1311867190.739265 depth/1311867190.739265.png
1311867190.763475 rgb/1311867190.763475.png 1311867190.775180 depth/1311867190.775180.png
1311867190.799433 rgb/1311867190.799433.png 1311867190.807090 depth/1311867190.807090.png
1311867190.831710 rgb/1311867190.831710.png 1311867190.841428 depth/1311867190.841428.png
1311867190.863426 rgb/1311867190.863426.png 1311867190.873925 depth/1311867190.873925.png
1311867190.899432 rgb/1311867190.899432.png 1311867190.907614 depth/1311867190.907614.png
1311867190.931647 rgb/1311867190.931647.png 1311867190.939360 depth/1311867190.939360.png
1311867190.963532 rgb/1311867190.963532.png 1311867190.974161 depth/1311867190.974161.png
1311867190.999440 rgb/1311867190.999440.png 1311867191.008595 depth/1311867191.008595.png
1311867191.031327 rgb/1311867191.031327.png 1311867191.039692 depth/1311867191.039692.png
1311867191.063627 rgb/1311867191.063627.png 1311867191.076433 depth/1311867191.076433.png
1311867191.099432 rgb/1311867191.099432.png 1311867191.110304 depth/1311867191.110304.png
1311867191.131303 rgb/1311867191.131303.png 1311867191.138814 depth/1311867191.138814.png
1311867191.163395 rgb/1311867191.163395.png 1311867191.174282 depth/1311867191.174282.png
1311867191.199389 rgb/1311867191.199389.png 1311867191.207792 depth/1311867191.207792.png
1311867191.231395 rgb/1311867191.231395.png 1311867191.240842 depth/1311867191.240842.png
1311867191.263468 rgb/1311867191.263468.png 1311867191.276958 depth/1311867191.276958.png
1311867191.299713 rgb/1311867191.299713.png 1311867191.308503 depth/1311867191.308503.png
1311867191.331660 rgb/1311867191.331660.png 1311867191.340478 depth/1311867191.340478.png
1311867191.363436 rgb/1311867191.363436.png 1311867191.379463 depth/1311867191.379463.png
1311867191.399571 rgb/1311867191.399571.png 1311867191.409158 depth/1311867191.409158.png
1311867191.431588 rgb/1311867191.431588.png 1311867191.441597 depth/1311867191.441597.png
1311867191.463414 rgb/1311867191.463414.png 1311867191.477531 depth/1311867191.477531.png
1311867191.499653 rgb/1311867191.499653.png 1311867191.507559 depth/1311867191.507559.png
1311867191.531446 rgb/1311867191.531446.png 1311867191.539062 depth/1311867191.539062.png
1311867191.563639 rgb/1311867191.563639.png 1311867191.576470 depth/1311867191.576470.png
1311867191.599847 rgb/1311867191.599847.png 1311867191.611867 depth/1311867191.611867.png
1311867191.631469 rgb/1311867191.631469.png 1311867191.645188 depth/1311867191.645188.png
1311867191.663620 rgb/1311867191.663620.png 1311867191.682792 depth/1311867191.682792.png
1311867191.699573 rgb/1311867191.699573.png 1311867191.711940 depth/1311867191.711940.png
1311867191.731487 rgb/1311867191.731487.png 1311867191.745720 depth/1311867191.745720.png
1311867191.763579 rgb/1311867191.763579.png 1311867191.776380 depth/1311867191.776380.png
1311867191.799771 rgb/1311867191.799771.png 1311867191.809725 depth/1311867191.809725.png
1311867191.831511 rgb/1311867191.831511.png 1311867191.839578 depth/1311867191.839578.png
1311867191.863471 rgb/1311867191.863471.png 1311867191.874522 depth/1311867191.874522.png
1311867191.899623 rgb/1311867191.899623.png 1311867191.907712 depth/1311867191.907712.png
1311867191.931630 rgb/1311867191.931630.png 1311867191.939160 depth/1311867191.939160.png
1311867191.963470 rgb/1311867191.963470.png 1311867191.975524 depth/1311867191.975524.png
1311867191.999526 rgb/1311867191.999526.png 1311867192.007629 depth/1311867192.007629.png
1311867192.031527 rgb/1311867192.031527.png 1311867192.044795 depth/1311867192.044795.png
1311867192.063495 rgb/1311867192.063495.png 1311867192.075193 depth/1311867192.075193.png
1311867192.099806 rgb/1311867192.099806.png 1311867192.107392 depth/1311867192.107392.png
1311867192.131666 rgb/1311867192.131666.png 1311867192.143303 depth/1311867192.143303.png
1311867192.163516 rgb/1311867192.163516.png 1311867192.175467 depth/1311867192.175467.png
1311867192.199653 rgb/1311867192.199653.png 1311867192.207754 depth/1311867192.207754.png
1311867192.231699 rgb/1311867192.231699.png 1311867192.245125 depth/1311867192.245125.png
1311867192.263542 rgb/1311867192.263542.png 1311867192.274463 depth/1311867192.274463.png
1311867192.299473 rgb/1311867192.299473.png 1311867192.306772 depth/1311867192.306772.png
1311867192.331519 rgb/1311867192.331519.png 1311867192.342739 depth/1311867192.342739.png
1311867192.363620 rgb/1311867192.363620.png 1311867192.375591 depth/1311867192.375591.png
1311867192.399491 rgb/1311867192.399491.png 1311867192.405934 depth/1311867192.405934.png
1311867192.431620 rgb/1311867192.431620.png 1311867192.444710 depth/1311867192.444710.png
1311867192.463542 rgb/1311867192.463542.png 1311867192.474821 depth/1311867192.474821.png
1311867192.499590 rgb/1311867192.499590.png 1311867192.507719 depth/1311867192.507719.png
1311867192.531620 rgb/1311867192.531620.png 1311867192.542782 depth/1311867192.542782.png
1311867192.563632 rgb/1311867192.563632.png 1311867192.578717 depth/1311867192.578717.png
1311867192.599632 rgb/1311867192.599632.png 1311867192.610993 depth/1311867192.610993.png
1311867192.631521 rgb/1311867192.631521.png 1311867192.643521 depth/1311867192.643521.png
1311867192.663625 rgb/1311867192.663625.png 1311867192.679014 depth/1311867192.679014.png
1311867192.699607 rgb/1311867192.699607.png 1311867192.711329 depth/1311867192.711329.png
1311867192.731618 rgb/1311867192.731618.png 1311867192.743962 depth/1311867192.743962.png
1311867192.763642 rgb/1311867192.763642.png 1311867192.776063 depth/1311867192.776063.png
1311867192.799500 rgb/1311867192.799500.png 1311867192.809187 depth/1311867192.809187.png
1311867192.831693 rgb/1311867192.831693.png 1311867192.842229 depth/1311867192.842229.png
1311867192.863604 rgb/1311867192.863604.png 1311867192.879289 depth/1311867192.879289.png
1311867192.899654 rgb/1311867192.899654.png 1311867192.909219 depth/1311867192.909219.png
1311867192.931656 rgb/1311867192.931656.png 1311867192.943411 depth/1311867192.943411.png
1311867192.963825 rgb/1311867192.963825.png 1311867192.977629 depth/1311867192.977629.png
1311867192.999714 rgb/1311867192.999714.png 1311867193.008681 depth/1311867193.008681.png
1311867193.031653 rgb/1311867193.031653.png 1311867193.043060 depth/1311867193.043060.png
1311867193.063616 rgb/1311867193.063616.png 1311867193.076737 depth/1311867193.076737.png
1311867193.099627 rgb/1311867193.099627.png 1311867193.110585 depth/1311867193.110585.png
1311867193.131636 rgb/1311867193.131636.png 1311867193.142922 depth/1311867193.142922.png
1311867193.163809 rgb/1311867193.163809.png 1311867193.176737 depth/1311867193.176737.png
1311867193.199592 rgb/1311867193.199592.png 1311867193.212268 depth/1311867193.212268.png
1311867193.231634 rgb/1311867193.231634.png 1311867193.243243 depth/1311867193.243243.png
1311867193.263554 rgb/1311867193.263554.png 1311867193.277390 depth/1311867193.277390.png
1311867193.299517 rgb/1311867193.299517.png 1311867193.313938 depth/1311867193.313938.png
1311867193.331430 rgb/1311867193.331430.png 1311867193.342667 depth/1311867193.342667.png
1311867193.363678 rgb/1311867193.363678.png 1311867193.378823 depth/1311867193.378823.png
1311867193.399557 rgb/1311867193.399557.png 1311867193.412674 depth/1311867193.412674.png
1311867193.431817 rgb/1311867193.431817.png 1311867193.444081 depth/1311867193.444081.png
1311867193.463559 rgb/1311867193.463559.png 1311867193.478297 depth/1311867193.478297.png
1311867193.531619 rgb/1311867193.531619.png 1311867193.543112 depth/1311867193.543112.png
1311867193.563584 rgb/1311867193.563584.png 1311867193.576571 depth/1311867193.576571.png
1311867193.599533 rgb/1311867193.599533.png 1311867193.612780 depth/1311867193.612780.png
1311867193.631742 rgb/1311867193.631742.png 1311867193.646145 depth/1311867193.646145.png
1311867193.663591 rgb/1311867193.663591.png 1311867193.675786 depth/1311867193.675786.png
1311867193.699539 rgb/1311867193.699539.png 1311867193.712289 depth/1311867193.712289.png
1311867193.731568 rgb/1311867193.731568.png 1311867193.743019 depth/1311867193.743019.png
1311867193.763567 rgb/1311867193.763567.png 1311867193.776017 depth/1311867193.776017.png
1311867193.799691 rgb/1311867193.799691.png 1311867193.813971 depth/1311867193.813971.png
1311867193.831554 rgb/1311867193.831554.png 1311867193.843676 depth/1311867193.843676.png
1311867193.863523 rgb/1311867193.863523.png 1311867193.877118 depth/1311867193.877118.png
1311867193.899690 rgb/1311867193.899690.png 1311867193.915123 depth/1311867193.915123.png
1311867193.931567 rgb/1311867193.931567.png 1311867193.942531 depth/1311867193.942531.png
1311867193.963704 rgb/1311867193.963704.png 1311867193.978177 depth/1311867193.978177.png
1311867193.999703 rgb/1311867193.999703.png 1311867194.014857 depth/1311867194.014857.png
1311867194.031689 rgb/1311867194.031689.png 1311867194.043344 depth/1311867194.043344.png
1311867194.063653 rgb/1311867194.063653.png 1311867194.074612 depth/1311867194.074612.png
1311867194.099680 rgb/1311867194.099680.png 1311867194.113106 depth/1311867194.113106.png
1311867194.131720 rgb/1311867194.131720.png 1311867194.142856 depth/1311867194.142856.png
1311867194.163586 rgb/1311867194.163586.png 1311867194.175855 depth/1311867194.175855.png
1311867194.199685 rgb/1311867194.199685.png 1311867194.213845 depth/1311867194.213845.png
1311867194.231549 rgb/1311867194.231549.png 1311867194.245114 depth/1311867194.245114.png
1311867194.263619 rgb/1311867194.263619.png 1311867194.276024 depth/1311867194.276024.png
1311867194.299716 rgb/1311867194.299716.png 1311867194.313920 depth/1311867194.313920.png
1311867194.331761 rgb/1311867194.331761.png 1311867194.344782 depth/1311867194.344782.png
1311867194.363706 rgb/1311867194.363706.png 1311867194.380223 depth/1311867194.380223.png
1311867194.399611 rgb/1311867194.399611.png 1311867194.412452 depth/1311867194.412452.png
1311867194.431803 rgb/1311867194.431803.png 1311867194.444751 depth/1311867194.444751.png
1311867194.463875 rgb/1311867194.463875.png 1311867194.480584 depth/1311867194.480584.png
1311867194.499629 rgb/1311867194.499629.png 1311867194.517493 depth/1311867194.517493.png
1311867194.531606 rgb/1311867194.531606.png 1311867194.543950 depth/1311867194.543950.png
1311867194.563736 rgb/1311867194.563736.png 1311867194.579598 depth/1311867194.579598.png
1311867194.599622 rgb/1311867194.599622.png 1311867194.612948 depth/1311867194.612948.png
1311867194.663614 rgb/1311867194.663614.png 1311867194.649388 depth/1311867194.649388.png
1311867194.699671 rgb/1311867194.699671.png 1311867194.713331 depth/1311867194.713331.png
1311867194.731755 rgb/1311867194.731755.png 1311867194.747510 depth/1311867194.747510.png
1311867194.763586 rgb/1311867194.763586.png 1311867194.778445 depth/1311867194.778445.png
1311867194.799726 rgb/1311867194.799726.png 1311867194.813039 depth/1311867194.813039.png
1311867194.831891 rgb/1311867194.831891.png 1311867194.847672 depth/1311867194.847672.png
1311867194.863668 rgb/1311867194.863668.png 1311867194.881415 depth/1311867194.881415.png
1311867194.899588 rgb/1311867194.899588.png 1311867194.910409 depth/1311867194.910409.png
1311867194.931823 rgb/1311867194.931823.png 1311867194.945145 depth/1311867194.945145.png
1311867194.963864 rgb/1311867194.963864.png 1311867194.978740 depth/1311867194.978740.png
1311867194.999857 rgb/1311867194.999857.png 1311867195.013280 depth/1311867195.013280.png
1311867195.031823 rgb/1311867195.031823.png 1311867195.046494 depth/1311867195.046494.png
1311867195.063659 rgb/1311867195.063659.png 1311867195.078171 depth/1311867195.078171.png
1311867195.099839 rgb/1311867195.099839.png 1311867195.111531 depth/1311867195.111531.png
1311867195.131755 rgb/1311867195.131755.png 1311867195.145831 depth/1311867195.145831.png
1311867195.163739 rgb/1311867195.163739.png 1311867195.178032 depth/1311867195.178032.png
1311867195.199682 rgb/1311867195.199682.png 1311867195.211475 depth/1311867195.211475.png
1311867195.231953 rgb/1311867195.231953.png 1311867195.243680 depth/1311867195.243680.png
1311867195.263959 rgb/1311867195.263959.png 1311867195.278040 depth/1311867195.278040.png
1311867195.299843 rgb/1311867195.299843.png 1311867195.312318 depth/1311867195.312318.png
1311867195.331663 rgb/1311867195.331663.png 1311867195.342598 depth/1311867195.342598.png
1311867195.363660 rgb/1311867195.363660.png 1311867195.378271 depth/1311867195.378271.png
1311867195.399819 rgb/1311867195.399819.png 1311867195.411983 depth/1311867195.411983.png
1311867195.431775 rgb/1311867195.431775.png 1311867195.443552 depth/1311867195.443552.png
1311867195.463774 rgb/1311867195.463774.png 1311867195.478824 depth/1311867195.478824.png
1311867195.499861 rgb/1311867195.499861.png 1311867195.511318 depth/1311867195.511318.png
1311867195.531827 rgb/1311867195.531827.png 1311867195.543962 depth/1311867195.543962.png
1311867195.563721 rgb/1311867195.563721.png 1311867195.578216 depth/1311867195.578216.png
1311867195.599756 rgb/1311867195.599756.png 1311867195.611986 depth/1311867195.611986.png
1311867195.631794 rgb/1311867195.631794.png 1311867195.643091 depth/1311867195.643091.png
1311867195.663755 rgb/1311867195.663755.png 1311867195.677913 depth/1311867195.677913.png
1311867195.699923 rgb/1311867195.699923.png 1311867195.710730 depth/1311867195.710730.png
1311867195.732032 rgb/1311867195.732032.png 1311867195.745830 depth/1311867195.745830.png
1311867195.767662 rgb/1311867195.767662.png 1311867195.782188 depth/1311867195.782188.png
1311867195.799635 rgb/1311867195.799635.png 1311867195.810050 depth/1311867195.810050.png
1311867195.831755 rgb/1311867195.831755.png 1311867195.845855 depth/1311867195.845855.png
1311867195.867630 rgb/1311867195.867630.png 1311867195.877866 depth/1311867195.877866.png
1311867195.899840 rgb/1311867195.899840.png 1311867195.909827 depth/1311867195.909827.png
1311867195.931915 rgb/1311867195.931915.png 1311867195.945846 depth/1311867195.945846.png
1311867195.967737 rgb/1311867195.967737.png 1311867195.977843 depth/1311867195.977843.png
1311867195.999658 rgb/1311867195.999658.png 1311867196.010057 depth/1311867196.010057.png
1311867196.031886 rgb/1311867196.031886.png 1311867196.049879 depth/1311867196.049879.png
1311867196.067754 rgb/1311867196.067754.png 1311867196.079311 depth/1311867196.079311.png
1311867196.099654 rgb/1311867196.099654.png 1311867196.111398 depth/1311867196.111398.png
1311867196.131796 rgb/1311867196.131796.png 1311867196.147329 depth/1311867196.147329.png
1311867196.167747 rgb/1311867196.167747.png 1311867196.181177 depth/1311867196.181177.png
1311867196.199711 rgb/1311867196.199711.png 1311867196.211495 depth/1311867196.211495.png
1311867196.231920 rgb/1311867196.231920.png 1311867196.246260 depth/1311867196.246260.png
1311867196.267924 rgb/1311867196.267924.png 1311867196.280057 depth/1311867196.280057.png
1311867196.299732 rgb/1311867196.299732.png 1311867196.311160 depth/1311867196.311160.png
1311867196.331833 rgb/1311867196.331833.png 1311867196.348473 depth/1311867196.348473.png
1311867196.368729 rgb/1311867196.368729.png 1311867196.384267 depth/1311867196.384267.png
1311867196.399739 rgb/1311867196.399739.png 1311867196.410755 depth/1311867196.410755.png
1311867196.432020 rgb/1311867196.432020.png 1311867196.446315 depth/1311867196.446315.png
1311867196.467800 rgb/1311867196.467800.png 1311867196.479832 depth/1311867196.479832.png
1311867196.499768 rgb/1311867196.499768.png 1311867196.511347 depth/1311867196.511347.png
1311867196.531926 rgb/1311867196.531926.png 1311867196.546842 depth/1311867196.546842.png
1311867196.567767 rgb/1311867196.567767.png 1311867196.579555 depth/1311867196.579555.png
1311867196.599713 rgb/1311867196.599713.png 1311867196.610893 depth/1311867196.610893.png
1311867196.667737 rgb/1311867196.667737.png 1311867196.680510 depth/1311867196.680510.png
1311867196.699700 rgb/1311867196.699700.png 1311867196.711210 depth/1311867196.711210.png
1311867196.731760 rgb/1311867196.731760.png 1311867196.746490 depth/1311867196.746490.png
1311867196.767707 rgb/1311867196.767707.png 1311867196.778375 depth/1311867196.778375.png
1311867196.799736 rgb/1311867196.799736.png 1311867196.810918 depth/1311867196.810918.png
1311867196.831867 rgb/1311867196.831867.png 1311867196.848875 depth/1311867196.848875.png
1311867196.867749 rgb/1311867196.867749.png 1311867196.882175 depth/1311867196.882175.png
1311867196.899715 rgb/1311867196.899715.png 1311867196.911570 depth/1311867196.911570.png
1311867196.931975 rgb/1311867196.931975.png 1311867196.948244 depth/1311867196.948244.png
1311867196.967911 rgb/1311867196.967911.png 1311867196.980988 depth/1311867196.980988.png
1311867196.999866 rgb/1311867196.999866.png 1311867197.015489 depth/1311867197.015489.png
1311867197.031979 rgb/1311867197.031979.png 1311867197.049068 depth/1311867197.049068.png
1311867197.067817 rgb/1311867197.067817.png 1311867197.080648 depth/1311867197.080648.png
1311867197.099836 rgb/1311867197.099836.png 1311867197.114811 depth/1311867197.114811.png
1311867197.131870 rgb/1311867197.131870.png 1311867197.146843 depth/1311867197.146843.png
1311867197.167713 rgb/1311867197.167713.png 1311867197.179243 depth/1311867197.179243.png
1311867197.199776 rgb/1311867197.199776.png 1311867197.214362 depth/1311867197.214362.png
1311867197.231928 rgb/1311867197.231928.png 1311867197.245929 depth/1311867197.245929.png
1311867197.267919 rgb/1311867197.267919.png 1311867197.279996 depth/1311867197.279996.png
1311867197.299810 rgb/1311867197.299810.png 1311867197.315726 depth/1311867197.315726.png
1311867197.332018 rgb/1311867197.332018.png 1311867197.346871 depth/1311867197.346871.png
1311867197.367855 rgb/1311867197.367855.png 1311867197.378402 depth/1311867197.378402.png
1311867197.399882 rgb/1311867197.399882.png 1311867197.415510 depth/1311867197.415510.png
1311867197.431956 rgb/1311867197.431956.png 1311867197.447888 depth/1311867197.447888.png
1311867197.467991 rgb/1311867197.467991.png 1311867197.479318 depth/1311867197.479318.png
1311867197.499995 rgb/1311867197.499995.png 1311867197.515076 depth/1311867197.515076.png
1311867197.531882 rgb/1311867197.531882.png 1311867197.546926 depth/1311867197.546926.png
1311867197.567869 rgb/1311867197.567869.png 1311867197.580275 depth/1311867197.580275.png
1311867197.599910 rgb/1311867197.599910.png 1311867197.615275 depth/1311867197.615275.png
1311867197.631963 rgb/1311867197.631963.png 1311867197.647044 depth/1311867197.647044.png
1311867197.667929 rgb/1311867197.667929.png 1311867197.680085 depth/1311867197.680085.png
1311867197.699744 rgb/1311867197.699744.png 1311867197.714329 depth/1311867197.714329.png
1311867197.732004 rgb/1311867197.732004.png 1311867197.746342 depth/1311867197.746342.png
1311867197.767904 rgb/1311867197.767904.png 1311867197.779301 depth/1311867197.779301.png
1311867197.799835 rgb/1311867197.799835.png 1311867197.814675 depth/1311867197.814675.png
1311867197.831987 rgb/1311867197.831987.png 1311867197.846792 depth/1311867197.846792.png
1311867197.867941 rgb/1311867197.867941.png 1311867197.880298 depth/1311867197.880298.png
1311867197.899954 rgb/1311867197.899954.png 1311867197.914861 depth/1311867197.914861.png
1311867197.932046 rgb/1311867197.932046.png 1311867197.947014 depth/1311867197.947014.png
1311867197.967946 rgb/1311867197.967946.png 1311867197.981270 depth/1311867197.981270.png
1311867197.999775 rgb/1311867197.999775.png 1311867198.014547 depth/1311867198.014547.png
1311867198.031819 rgb/1311867198.031819.png 1311867198.046337 depth/1311867198.046337.png
1311867198.067816 rgb/1311867198.067816.png 1311867198.078707 depth/1311867198.078707.png
1311867198.099796 rgb/1311867198.099796.png 1311867198.114377 depth/1311867198.114377.png
1311867198.131829 rgb/1311867198.131829.png 1311867198.146361 depth/1311867198.146361.png
1311867198.167952 rgb/1311867198.167952.png 1311867198.182252 depth/1311867198.182252.png
1311867198.199814 rgb/1311867198.199814.png 1311867198.214499 depth/1311867198.214499.png
1311867198.232003 rgb/1311867198.232003.png 1311867198.246412 depth/1311867198.246412.png
1311867198.267962 rgb/1311867198.267962.png 1311867198.282158 depth/1311867198.282158.png
1311867198.331863 rgb/1311867198.331863.png 1311867198.315912 depth/1311867198.315912.png
1311867198.367970 rgb/1311867198.367970.png 1311867198.382832 depth/1311867198.382832.png
1311867198.431988 rgb/1311867198.431988.png 1311867198.424268 depth/1311867198.424268.png
1311867198.467921 rgb/1311867198.467921.png 1311867198.449786 depth/1311867198.449786.png
1311867198.500075 rgb/1311867198.500075.png 1311867198.485622 depth/1311867198.485622.png
1311867198.532125 rgb/1311867198.532125.png 1311867198.519034 depth/1311867198.519034.png
1311867198.567990 rgb/1311867198.567990.png 1311867198.582424 depth/1311867198.582424.png
1311867198.599951 rgb/1311867198.599951.png 1311867198.614749 depth/1311867198.614749.png
1311867198.631966 rgb/1311867198.631966.png 1311867198.648201 depth/1311867198.648201.png
1311867198.668073 rgb/1311867198.668073.png 1311867198.682754 depth/1311867198.682754.png
1311867198.699844 rgb/1311867198.699844.png 1311867198.714652 depth/1311867198.714652.png
1311867198.731874 rgb/1311867198.731874.png 1311867198.746770 depth/1311867198.746770.png
1311867198.767911 rgb/1311867198.767911.png 1311867198.784270 depth/1311867198.784270.png
1311867198.799839 rgb/1311867198.799839.png 1311867198.814942 depth/1311867198.814942.png
1311867198.831953 rgb/1311867198.831953.png 1311867198.846401 depth/1311867198.846401.png
1311867198.867891 rgb/1311867198.867891.png 1311867198.884537 depth/1311867198.884537.png
1311867198.899855 rgb/1311867198.899855.png 1311867198.914793 depth/1311867198.914793.png
1311867198.931881 rgb/1311867198.931881.png 1311867198.946518 depth/1311867198.946518.png
1311867198.968077 rgb/1311867198.968077.png 1311867198.983933 depth/1311867198.983933.png
1311867199.000050 rgb/1311867199.000050.png 1311867199.014873 depth/1311867199.014873.png
1311867199.031843 rgb/1311867199.031843.png 1311867199.046801 depth/1311867199.046801.png
1311867199.099860 rgb/1311867199.099860.png 1311867199.084932 depth/1311867199.084932.png
1311867199.132002 rgb/1311867199.132002.png 1311867199.146542 depth/1311867199.146542.png
1311867199.167891 rgb/1311867199.167891.png 1311867199.182366 depth/1311867199.182366.png
1311867199.200126 rgb/1311867199.200126.png 1311867199.214668 depth/1311867199.214668.png
1311867199.234099 rgb/1311867199.234099.png 1311867199.246775 depth/1311867199.246775.png
1311867199.267942 rgb/1311867199.267942.png 1311867199.283359 depth/1311867199.283359.png
1311867199.300030 rgb/1311867199.300030.png 1311867199.315913 depth/1311867199.315913.png
1311867199.331880 rgb/1311867199.331880.png 1311867199.346521 depth/1311867199.346521.png
1311867199.368141 rgb/1311867199.368141.png 1311867199.382905 depth/1311867199.382905.png
1311867199.399920 rgb/1311867199.399920.png 1311867199.414759 depth/1311867199.414759.png
1311867199.432048 rgb/1311867199.432048.png 1311867199.451291 depth/1311867199.451291.png
1311867199.467972 rgb/1311867199.467972.png 1311867199.483736 depth/1311867199.483736.png
1311867199.500181 rgb/1311867199.500181.png 1311867199.515020 depth/1311867199.515020.png
1311867199.568266 rgb/1311867199.568266.png 1311867199.554406 depth/1311867199.554406.png
1311867199.600399 rgb/1311867199.600399.png 1311867199.615831 depth/1311867199.615831.png
1311867199.668054 rgb/1311867199.668054.png 1311867199.653846 depth/1311867199.653846.png
1311867199.699941 rgb/1311867199.699941.png 1311867199.714676 depth/1311867199.714676.png
1311867199.732005 rgb/1311867199.732005.png 1311867199.751154 depth/1311867199.751154.png
1311867199.768069 rgb/1311867199.768069.png 1311867199.782602 depth/1311867199.782602.png
1311867199.800056 rgb/1311867199.800056.png 1311867199.815015 depth/1311867199.815015.png
1311867199.832480 rgb/1311867199.832480.png 1311867199.851905 depth/1311867199.851905.png
1311867199.867939 rgb/1311867199.867939.png 1311867199.883961 depth/1311867199.883961.png
1311867199.899922 rgb/1311867199.899922.png 1311867199.914816 depth/1311867199.914816.png
1311867199.932206 rgb/1311867199.932206.png 1311867199.952071 depth/1311867199.952071.png
1311867199.967970 rgb/1311867199.967970.png 1311867199.982841 depth/1311867199.982841.png
1311867200.000052 rgb/1311867200.000052.png 1311867200.014403 depth/1311867200.014403.png
1311867200.068006 rgb/1311867200.068006.png 1311867200.053964 depth/1311867200.053964.png
1311867200.100058 rgb/1311867200.100058.png 1311867200.083033 depth/1311867200.083033.png
1311867200.132173 rgb/1311867200.132173.png 1311867200.117447 depth/1311867200.117447.png
1311867200.168054 rgb/1311867200.168054.png 1311867200.151700 depth/1311867200.151700.png
1311867200.200062 rgb/1311867200.200062.png 1311867200.185322 depth/1311867200.185322.png
1311867200.232126 rgb/1311867200.232126.png 1311867200.217906 depth/1311867200.217906.png
1311867200.268192 rgb/1311867200.268192.png 1311867200.282543 depth/1311867200.282543.png
1311867200.300066 rgb/1311867200.300066.png 1311867200.314888 depth/1311867200.314888.png
1311867200.332117 rgb/1311867200.332117.png 1311867200.351499 depth/1311867200.351499.png
1311867200.368163 rgb/1311867200.368163.png 1311867200.383776 depth/1311867200.383776.png
1311867200.432114 rgb/1311867200.432114.png 1311867200.416280 depth/1311867200.416280.png
1311867200.468132 rgb/1311867200.468132.png 1311867200.452249 depth/1311867200.452249.png
1311867200.500090 rgb/1311867200.500090.png 1311867200.514392 depth/1311867200.514392.png
1311867200.532161 rgb/1311867200.532161.png 1311867200.550503 depth/1311867200.550503.png
1311867200.568212 rgb/1311867200.568212.png 1311867200.583222 depth/1311867200.583222.png
1311867200.600091 rgb/1311867200.600091.png 1311867200.614561 depth/1311867200.614561.png
1311867200.668204 rgb/1311867200.668204.png 1311867200.650478 depth/1311867200.650478.png
1311867200.700120 rgb/1311867200.700120.png 1311867200.685128 depth/1311867200.685128.png
1311867200.732170 rgb/1311867200.732170.png 1311867200.718972 depth/1311867200.718972.png
1311867200.768079 rgb/1311867200.768079.png 1311867200.783293 depth/1311867200.783293.png
1311867200.832137 rgb/1311867200.832137.png 1311867200.818107 depth/1311867200.818107.png
1311867200.868158 rgb/1311867200.868158.png 1311867200.850150 depth/1311867200.850150.png
1311867200.899995 rgb/1311867200.899995.png 1311867200.884537 depth/1311867200.884537.png
1311867200.932029 rgb/1311867200.932029.png 1311867200.919493 depth/1311867200.919493.png
1311867200.968154 rgb/1311867200.968154.png 1311867200.951268 depth/1311867200.951268.png
1311867201.000062 rgb/1311867201.000062.png 1311867200.985601 depth/1311867200.985601.png
1311867201.032193 rgb/1311867201.032193.png 1311867201.018440 depth/1311867201.018440.png
1311867201.067956 rgb/1311867201.067956.png 1311867201.055518 depth/1311867201.055518.png
1311867201.100217 rgb/1311867201.100217.png 1311867201.082543 depth/1311867201.082543.png
1311867201.132242 rgb/1311867201.132242.png 1311867201.119345 depth/1311867201.119345.png
1311867201.168191 rgb/1311867201.168191.png 1311867201.183016 depth/1311867201.183016.png
1311867201.232056 rgb/1311867201.232056.png 1311867201.219653 depth/1311867201.219653.png
1311867201.269490 rgb/1311867201.269490.png 1311867201.282410 depth/1311867201.282410.png
1311867201.332276 rgb/1311867201.332276.png 1311867201.318054 depth/1311867201.318054.png
1311867201.368233 rgb/1311867201.368233.png 1311867201.352220 depth/1311867201.352220.png
1311867201.400227 rgb/1311867201.400227.png 1311867201.384279 depth/1311867201.384279.png
1311867201.432761 rgb/1311867201.432761.png 1311867201.419876 depth/1311867201.419876.png
1311867201.468080 rgb/1311867201.468080.png 1311867201.455858 depth/1311867201.455858.png
1311867201.500087 rgb/1311867201.500087.png 1311867201.485311 depth/1311867201.485311.png
1311867201.532195 rgb/1311867201.532195.png 1311867201.519869 depth/1311867201.519869.png
1311867201.568143 rgb/1311867201.568143.png 1311867201.552774 depth/1311867201.552774.png
1311867201.600103 rgb/1311867201.600103.png 1311867201.584022 depth/1311867201.584022.png
1311867201.632068 rgb/1311867201.632068.png 1311867201.619705 depth/1311867201.619705.png
1311867201.668050 rgb/1311867201.668050.png 1311867201.683945 depth/1311867201.683945.png
1311867201.732200 rgb/1311867201.732200.png 1311867201.718901 depth/1311867201.718901.png
1311867201.768201 rgb/1311867201.768201.png 1311867201.750729 depth/1311867201.750729.png
1311867201.800210 rgb/1311867201.800210.png 1311867201.785805 depth/1311867201.785805.png
1311867201.832156 rgb/1311867201.832156.png 1311867201.819018 depth/1311867201.819018.png
1311867201.868219 rgb/1311867201.868219.png 1311867201.850574 depth/1311867201.850574.png
1311867201.900077 rgb/1311867201.900077.png 1311867201.886285 depth/1311867201.886285.png
1311867201.932262 rgb/1311867201.932262.png 1311867201.919573 depth/1311867201.919573.png
1311867201.968172 rgb/1311867201.968172.png 1311867201.951652 depth/1311867201.951652.png
1311867202.000190 rgb/1311867202.000190.png 1311867201.989460 depth/1311867201.989460.png
1311867202.032239 rgb/1311867202.032239.png 1311867202.018488 depth/1311867202.018488.png
1311867202.068152 rgb/1311867202.068152.png 1311867202.050736 depth/1311867202.050736.png
1311867202.100315 rgb/1311867202.100315.png 1311867202.086635 depth/1311867202.086635.png
1311867202.132409 rgb/1311867202.132409.png 1311867202.118592 depth/1311867202.118592.png
1311867202.168279 rgb/1311867202.168279.png 1311867202.151662 depth/1311867202.151662.png
1311867202.200125 rgb/1311867202.200125.png 1311867202.186626 depth/1311867202.186626.png
1311867202.232375 rgb/1311867202.232375.png 1311867202.219127 depth/1311867202.219127.png
1311867202.268101 rgb/1311867202.268101.png 1311867202.251322 depth/1311867202.251322.png
1311867202.300107 rgb/1311867202.300107.png 1311867202.286828 depth/1311867202.286828.png
1311867202.332365 rgb/1311867202.332365.png 1311867202.319988 depth/1311867202.319988.png
1311867202.368310 rgb/1311867202.368310.png 1311867202.352390 depth/1311867202.352390.png
1311867202.400292 rgb/1311867202.400292.png 1311867202.388363 depth/1311867202.388363.png
1311867202.432186 rgb/1311867202.432186.png 1311867202.419639 depth/1311867202.419639.png
1311867202.468118 rgb/1311867202.468118.png 1311867202.452943 depth/1311867202.452943.png
1311867202.500244 rgb/1311867202.500244.png 1311867202.487571 depth/1311867202.487571.png
1311867202.532280 rgb/1311867202.532280.png 1311867202.520645 depth/1311867202.520645.png
1311867202.568183 rgb/1311867202.568183.png 1311867202.550894 depth/1311867202.550894.png
1311867202.600241 rgb/1311867202.600241.png 1311867202.586495 depth/1311867202.586495.png
1311867202.632409 rgb/1311867202.632409.png 1311867202.618503 depth/1311867202.618503.png
1311867202.668254 rgb/1311867202.668254.png 1311867202.651445 depth/1311867202.651445.png
1311867202.700291 rgb/1311867202.700291.png 1311867202.686656 depth/1311867202.686656.png
1311867202.732284 rgb/1311867202.732284.png 1311867202.718536 depth/1311867202.718536.png
1311867202.768106 rgb/1311867202.768106.png 1311867202.750735 depth/1311867202.750735.png
1311867202.800215 rgb/1311867202.800215.png 1311867202.789717 depth/1311867202.789717.png
1311867202.832371 rgb/1311867202.832371.png 1311867202.819000 depth/1311867202.819000.png
1311867202.868186 rgb/1311867202.868186.png 1311867202.852758 depth/1311867202.852758.png
1311867202.900343 rgb/1311867202.900343.png 1311867202.887322 depth/1311867202.887322.png
1311867202.932160 rgb/1311867202.932160.png 1311867202.919988 depth/1311867202.919988.png
1311867202.968198 rgb/1311867202.968198.png 1311867202.952569 depth/1311867202.952569.png
1311867203.000234 rgb/1311867203.000234.png 1311867202.986871 depth/1311867202.986871.png
1311867203.032284 rgb/1311867203.032284.png 1311867203.020202 depth/1311867203.020202.png
1311867203.068187 rgb/1311867203.068187.png 1311867203.056085 depth/1311867203.056085.png
1311867203.100350 rgb/1311867203.100350.png 1311867203.086578 depth/1311867203.086578.png
1311867203.132443 rgb/1311867203.132443.png 1311867203.118993 depth/1311867203.118993.png
1311867203.168210 rgb/1311867203.168210.png 1311867203.154982 depth/1311867203.154982.png
1311867203.200286 rgb/1311867203.200286.png 1311867203.187794 depth/1311867203.187794.png
1311867203.232211 rgb/1311867203.232211.png 1311867203.218591 depth/1311867203.218591.png
1311867203.268183 rgb/1311867203.268183.png 1311867203.255203 depth/1311867203.255203.png
1311867203.300206 rgb/1311867203.300206.png 1311867203.286480 depth/1311867203.286480.png
1311867203.332226 rgb/1311867203.332226.png 1311867203.319467 depth/1311867203.319467.png
1311867203.368129 rgb/1311867203.368129.png 1311867203.354746 depth/1311867203.354746.png
1311867203.400200 rgb/1311867203.400200.png 1311867203.386560 depth/1311867203.386560.png
1311867203.432255 rgb/1311867203.432255.png 1311867203.418361 depth/1311867203.418361.png
1311867203.468205 rgb/1311867203.468205.png 1311867203.454512 depth/1311867203.454512.png
1311867203.500494 rgb/1311867203.500494.png 1311867203.486444 depth/1311867203.486444.png
1311867203.532247 rgb/1311867203.532247.png 1311867203.518554 depth/1311867203.518554.png
1311867203.568287 rgb/1311867203.568287.png 1311867203.556026 depth/1311867203.556026.png
1311867203.600247 rgb/1311867203.600247.png 1311867203.587655 depth/1311867203.587655.png
1311867203.632381 rgb/1311867203.632381.png 1311867203.619198 depth/1311867203.619198.png
1311867203.668366 rgb/1311867203.668366.png 1311867203.655772 depth/1311867203.655772.png
1311867203.700467 rgb/1311867203.700467.png 1311867203.686675 depth/1311867203.686675.png
1311867203.732263 rgb/1311867203.732263.png 1311867203.719526 depth/1311867203.719526.png
1311867203.768142 rgb/1311867203.768142.png 1311867203.756642 depth/1311867203.756642.png
1311867203.800188 rgb/1311867203.800188.png 1311867203.786723 depth/1311867203.786723.png
1311867203.832438 rgb/1311867203.832438.png 1311867203.819386 depth/1311867203.819386.png
1311867203.868154 rgb/1311867203.868154.png 1311867203.857286 depth/1311867203.857286.png
1311867203.900206 rgb/1311867203.900206.png 1311867203.889189 depth/1311867203.889189.png
1311867203.932460 rgb/1311867203.932460.png 1311867203.918802 depth/1311867203.918802.png
1311867203.968287 rgb/1311867203.968287.png 1311867203.955349 depth/1311867203.955349.png
1311867204.000337 rgb/1311867204.000337.png 1311867203.986637 depth/1311867203.986637.png
1311867204.032369 rgb/1311867204.032369.png 1311867204.019985 depth/1311867204.019985.png
1311867204.068206 rgb/1311867204.068206.png 1311867204.055151 depth/1311867204.055151.png
1311867204.100343 rgb/1311867204.100343.png 1311867204.086751 depth/1311867204.086751.png
1311867204.132295 rgb/1311867204.132295.png 1311867204.119153 depth/1311867204.119153.png
1311867204.168262 rgb/1311867204.168262.png 1311867204.155577 depth/1311867204.155577.png
1311867204.200305 rgb/1311867204.200305.png 1311867204.187653 depth/1311867204.187653.png
1311867204.232436 rgb/1311867204.232436.png 1311867204.218777 depth/1311867204.218777.png
1311867204.268181 rgb/1311867204.268181.png 1311867204.256644 depth/1311867204.256644.png
1311867204.300302 rgb/1311867204.300302.png 1311867204.286714 depth/1311867204.286714.png
1311867204.332519 rgb/1311867204.332519.png 1311867204.320454 depth/1311867204.320454.png
1311867204.368375 rgb/1311867204.368375.png 1311867204.362574 depth/1311867204.362574.png
1311867204.400282 rgb/1311867204.400282.png 1311867204.386960 depth/1311867204.386960.png
1311867204.432434 rgb/1311867204.432434.png 1311867204.424097 depth/1311867204.424097.png
1311867204.468296 rgb/1311867204.468296.png 1311867204.454995 depth/1311867204.454995.png
1311867204.500277 rgb/1311867204.500277.png 1311867204.487275 depth/1311867204.487275.png
1311867204.532479 rgb/1311867204.532479.png 1311867204.523722 depth/1311867204.523722.png
1311867204.568211 rgb/1311867204.568211.png 1311867204.558186 depth/1311867204.558186.png
1311867204.600264 rgb/1311867204.600264.png 1311867204.587847 depth/1311867204.587847.png
1311867204.632418 rgb/1311867204.632418.png 1311867204.624153 depth/1311867204.624153.png
1311867204.668452 rgb/1311867204.668452.png 1311867204.654182 depth/1311867204.654182.png
1311867204.700261 rgb/1311867204.700261.png 1311867204.687154 depth/1311867204.687154.png
1311867204.732293 rgb/1311867204.732293.png 1311867204.722569 depth/1311867204.722569.png
1311867204.768312 rgb/1311867204.768312.png 1311867204.753951 depth/1311867204.753951.png
1311867204.800434 rgb/1311867204.800434.png 1311867204.787872 depth/1311867204.787872.png
1311867204.832496 rgb/1311867204.832496.png 1311867204.822720 depth/1311867204.822720.png
1311867204.868246 rgb/1311867204.868246.png 1311867204.854267 depth/1311867204.854267.png
1311867204.900224 rgb/1311867204.900224.png 1311867204.886496 depth/1311867204.886496.png
1311867204.936363 rgb/1311867204.936363.png 1311867204.922022 depth/1311867204.922022.png
1311867204.968219 rgb/1311867204.968219.png 1311867204.954292 depth/1311867204.954292.png
1311867205.000335 rgb/1311867205.000335.png 1311867204.986600 depth/1311867204.986600.png
1311867205.036326 rgb/1311867205.036326.png 1311867205.022724 depth/1311867205.022724.png
1311867205.068637 rgb/1311867205.068637.png 1311867205.055081 depth/1311867205.055081.png
1311867205.100765 rgb/1311867205.100765.png 1311867205.088100 depth/1311867205.088100.png
1311867205.136301 rgb/1311867205.136301.png 1311867205.123245 depth/1311867205.123245.png
1311867205.168290 rgb/1311867205.168290.png 1311867205.154532 depth/1311867205.154532.png
1311867205.200371 rgb/1311867205.200371.png 1311867205.186351 depth/1311867205.186351.png
1311867205.236444 rgb/1311867205.236444.png 1311867205.222313 depth/1311867205.222313.png
1311867205.268392 rgb/1311867205.268392.png 1311867205.254185 depth/1311867205.254185.png
1311867205.300458 rgb/1311867205.300458.png 1311867205.288050 depth/1311867205.288050.png
1311867205.336288 rgb/1311867205.336288.png 1311867205.321888 depth/1311867205.321888.png
1311867205.368439 rgb/1311867205.368439.png 1311867205.354290 depth/1311867205.354290.png
1311867205.400476 rgb/1311867205.400476.png 1311867205.386278 depth/1311867205.386278.png
1311867205.436290 rgb/1311867205.436290.png 1311867205.422565 depth/1311867205.422565.png
1311867205.468361 rgb/1311867205.468361.png 1311867205.454042 depth/1311867205.454042.png
1311867205.500259 rgb/1311867205.500259.png 1311867205.486512 depth/1311867205.486512.png
1311867205.536285 rgb/1311867205.536285.png 1311867205.523034 depth/1311867205.523034.png
1311867205.568369 rgb/1311867205.568369.png 1311867205.554290 depth/1311867205.554290.png
1311867205.600318 rgb/1311867205.600318.png 1311867205.586684 depth/1311867205.586684.png
1311867205.636378 rgb/1311867205.636378.png 1311867205.622618 depth/1311867205.622618.png
1311867205.668640 rgb/1311867205.668640.png 1311867205.655598 depth/1311867205.655598.png
1311867205.700293 rgb/1311867205.700293.png 1311867205.690296 depth/1311867205.690296.png
1311867205.736482 rgb/1311867205.736482.png 1311867205.722206 depth/1311867205.722206.png
1311867205.768331 rgb/1311867205.768331.png 1311867205.754835 depth/1311867205.754835.png
1311867205.800294 rgb/1311867205.800294.png 1311867205.790638 depth/1311867205.790638.png
1311867205.836370 rgb/1311867205.836370.png 1311867205.823211 depth/1311867205.823211.png
1311867205.868513 rgb/1311867205.868513.png 1311867205.855476 depth/1311867205.855476.png
1311867205.900317 rgb/1311867205.900317.png 1311867205.890588 depth/1311867205.890588.png
1311867205.936313 rgb/1311867205.936313.png 1311867205.922302 depth/1311867205.922302.png
1311867205.968515 rgb/1311867205.968515.png 1311867205.954494 depth/1311867205.954494.png
1311867206.000654 rgb/1311867206.000654.png 1311867205.990585 depth/1311867205.990585.png
1311867206.036736 rgb/1311867206.036736.png 1311867206.025985 depth/1311867206.025985.png
1311867206.068413 rgb/1311867206.068413.png 1311867206.060425 depth/1311867206.060425.png
1311867206.100418 rgb/1311867206.100418.png 1311867206.090329 depth/1311867206.090329.png
1311867206.136422 rgb/1311867206.136422.png 1311867206.122754 depth/1311867206.122754.png
1311867206.168280 rgb/1311867206.168280.png 1311867206.154613 depth/1311867206.154613.png
1311867206.200431 rgb/1311867206.200431.png 1311867206.190380 depth/1311867206.190380.png
1311867206.236354 rgb/1311867206.236354.png 1311867206.223956 depth/1311867206.223956.png
1311867206.268562 rgb/1311867206.268562.png 1311867206.255358 depth/1311867206.255358.png
1311867206.300429 rgb/1311867206.300429.png 1311867206.290477 depth/1311867206.290477.png
1311867206.336618 rgb/1311867206.336618.png 1311867206.322204 depth/1311867206.322204.png
1311867206.368476 rgb/1311867206.368476.png 1311867206.354253 depth/1311867206.354253.png
1311867206.400411 rgb/1311867206.400411.png 1311867206.390007 depth/1311867206.390007.png
1311867206.436540 rgb/1311867206.436540.png 1311867206.422026 depth/1311867206.422026.png
1311867206.468475 rgb/1311867206.468475.png 1311867206.454231 depth/1311867206.454231.png
1311867206.500567 rgb/1311867206.500567.png 1311867206.490538 depth/1311867206.490538.png
1311867206.536578 rgb/1311867206.536578.png 1311867206.525033 depth/1311867206.525033.png
1311867206.568318 rgb/1311867206.568318.png 1311867206.553930 depth/1311867206.553930.png
1311867206.600453 rgb/1311867206.600453.png 1311867206.592113 depth/1311867206.592113.png
1311867206.636480 rgb/1311867206.636480.png 1311867206.622636 depth/1311867206.622636.png
1311867206.668513 rgb/1311867206.668513.png 1311867206.656675 depth/1311867206.656675.png
1311867206.700560 rgb/1311867206.700560.png 1311867206.694521 depth/1311867206.694521.png
1311867206.736376 rgb/1311867206.736376.png 1311867206.724848 depth/1311867206.724848.png
1311867206.768348 rgb/1311867206.768348.png 1311867206.758797 depth/1311867206.758797.png
1311867206.800520 rgb/1311867206.800520.png 1311867206.790284 depth/1311867206.790284.png
1311867206.836416 rgb/1311867206.836416.png 1311867206.822977 depth/1311867206.822977.png
1311867206.868563 rgb/1311867206.868563.png 1311867206.860545 depth/1311867206.860545.png
1311867206.900569 rgb/1311867206.900569.png 1311867206.890777 depth/1311867206.890777.png
1311867206.936441 rgb/1311867206.936441.png 1311867206.922502 depth/1311867206.922502.png
1311867206.968607 rgb/1311867206.968607.png 1311867206.959248 depth/1311867206.959248.png
1311867207.000644 rgb/1311867207.000644.png 1311867206.994868 depth/1311867206.994868.png
1311867207.036586 rgb/1311867207.036586.png 1311867207.024755 depth/1311867207.024755.png
1311867207.068407 rgb/1311867207.068407.png 1311867207.059726 depth/1311867207.059726.png
1311867207.100546 rgb/1311867207.100546.png 1311867207.094280 depth/1311867207.094280.png
1311867207.136473 rgb/1311867207.136473.png 1311867207.122914 depth/1311867207.122914.png
1311867207.168707 rgb/1311867207.168707.png 1311867207.158355 depth/1311867207.158355.png
1311867207.200654 rgb/1311867207.200654.png 1311867207.190492 depth/1311867207.190492.png
1311867207.236587 rgb/1311867207.236587.png 1311867207.222618 depth/1311867207.222618.png
1311867207.268617 rgb/1311867207.268617.png 1311867207.260483 depth/1311867207.260483.png
1311867207.300500 rgb/1311867207.300500.png 1311867207.292690 depth/1311867207.292690.png
1311867207.336652 rgb/1311867207.336652.png 1311867207.323524 depth/1311867207.323524.png
1311867207.368579 rgb/1311867207.368579.png 1311867207.359748 depth/1311867207.359748.png
1311867207.400698 rgb/1311867207.400698.png 1311867207.390131 depth/1311867207.390131.png
1311867207.436580 rgb/1311867207.436580.png 1311867207.422784 depth/1311867207.422784.png
1311867207.468647 rgb/1311867207.468647.png 1311867207.458679 depth/1311867207.458679.png
1311867207.500601 rgb/1311867207.500601.png 1311867207.492764 depth/1311867207.492764.png
1311867207.536508 rgb/1311867207.536508.png 1311867207.523730 depth/1311867207.523730.png
1311867207.568706 rgb/1311867207.568706.png 1311867207.559841 depth/1311867207.559841.png
1311867207.600587 rgb/1311867207.600587.png 1311867207.594480 depth/1311867207.594480.png
1311867207.636491 rgb/1311867207.636491.png 1311867207.625922 depth/1311867207.625922.png
1311867207.668773 rgb/1311867207.668773.png 1311867207.659294 depth/1311867207.659294.png
1311867207.700562 rgb/1311867207.700562.png 1311867207.692309 depth/1311867207.692309.png
1311867207.736501 rgb/1311867207.736501.png 1311867207.723864 depth/1311867207.723864.png
1311867207.768609 rgb/1311867207.768609.png 1311867207.758805 depth/1311867207.758805.png
1311867207.800991 rgb/1311867207.800991.png 1311867207.792192 depth/1311867207.792192.png
1311867207.836554 rgb/1311867207.836554.png 1311867207.823776 depth/1311867207.823776.png
1311867207.868773 rgb/1311867207.868773.png 1311867207.860848 depth/1311867207.860848.png
1311867207.900900 rgb/1311867207.900900.png 1311867207.893709 depth/1311867207.893709.png
1311867207.936534 rgb/1311867207.936534.png 1311867207.924414 depth/1311867207.924414.png
1311867207.968490 rgb/1311867207.968490.png 1311867207.961497 depth/1311867207.961497.png
1311867208.000665 rgb/1311867208.000665.png 1311867207.991413 depth/1311867207.991413.png
1311867208.036765 rgb/1311867208.036765.png 1311867208.024850 depth/1311867208.024850.png
1311867208.069925 rgb/1311867208.069925.png 1311867208.061850 depth/1311867208.061850.png
1311867208.101134 rgb/1311867208.101134.png 1311867208.092462 depth/1311867208.092462.png
1311867208.136633 rgb/1311867208.136633.png 1311867208.127656 depth/1311867208.127656.png
1311867208.168683 rgb/1311867208.168683.png 1311867208.159607 depth/1311867208.159607.png
1311867208.200521 rgb/1311867208.200521.png 1311867208.190501 depth/1311867208.190501.png
1311867208.236561 rgb/1311867208.236561.png 1311867208.228085 depth/1311867208.228085.png
1311867208.268440 rgb/1311867208.268440.png 1311867208.258179 depth/1311867208.258179.png
1311867208.300597 rgb/1311867208.300597.png 1311867208.290199 depth/1311867208.290199.png
1311867208.336528 rgb/1311867208.336528.png 1311867208.327021 depth/1311867208.327021.png
1311867208.368511 rgb/1311867208.368511.png 1311867208.358097 depth/1311867208.358097.png
1311867208.400592 rgb/1311867208.400592.png 1311867208.391056 depth/1311867208.391056.png
1311867208.436460 rgb/1311867208.436460.png 1311867208.426023 depth/1311867208.426023.png
1311867208.468664 rgb/1311867208.468664.png 1311867208.457742 depth/1311867208.457742.png
1311867208.500564 rgb/1311867208.500564.png 1311867208.490765 depth/1311867208.490765.png
1311867208.536522 rgb/1311867208.536522.png 1311867208.525741 depth/1311867208.525741.png
1311867208.568644 rgb/1311867208.568644.png 1311867208.558380 depth/1311867208.558380.png
1311867208.600595 rgb/1311867208.600595.png 1311867208.590450 depth/1311867208.590450.png
1311867208.636445 rgb/1311867208.636445.png 1311867208.625978 depth/1311867208.625978.png
1311867208.668488 rgb/1311867208.668488.png 1311867208.658208 depth/1311867208.658208.png
1311867208.700606 rgb/1311867208.700606.png 1311867208.691030 depth/1311867208.691030.png
1311867208.736710 rgb/1311867208.736710.png 1311867208.726226 depth/1311867208.726226.png
1311867208.768807 rgb/1311867208.768807.png 1311867208.759101 depth/1311867208.759101.png
1311867208.800641 rgb/1311867208.800641.png 1311867208.790975 depth/1311867208.790975.png
1311867208.836883 rgb/1311867208.836883.png 1311867208.825993 depth/1311867208.825993.png
1311867208.868491 rgb/1311867208.868491.png 1311867208.858819 depth/1311867208.858819.png
1311867208.900811 rgb/1311867208.900811.png 1311867208.891626 depth/1311867208.891626.png
1311867208.936516 rgb/1311867208.936516.png 1311867208.927512 depth/1311867208.927512.png
1311867208.968732 rgb/1311867208.968732.png 1311867208.957776 depth/1311867208.957776.png
1311867209.000767 rgb/1311867209.000767.png 1311867208.991164 depth/1311867208.991164.png
1311867209.036589 rgb/1311867209.036589.png 1311867209.027078 depth/1311867209.027078.png
1311867209.068848 rgb/1311867209.068848.png 1311867209.057957 depth/1311867209.057957.png
1311867209.100837 rgb/1311867209.100837.png 1311867209.090698 depth/1311867209.090698.png
1311867209.145248 rgb/1311867209.145248.png 1311867209.126078 depth/1311867209.126078.png
1311867209.168676 rgb/1311867209.168676.png 1311867209.160062 depth/1311867209.160062.png
1311867209.200608 rgb/1311867209.200608.png 1311867209.191784 depth/1311867209.191784.png
1311867209.236579 rgb/1311867209.236579.png 1311867209.225953 depth/1311867209.225953.png
1311867209.268677 rgb/1311867209.268677.png 1311867209.258006 depth/1311867209.258006.png
1311867209.300548 rgb/1311867209.300548.png 1311867209.290313 depth/1311867209.290313.png
1311867209.336608 rgb/1311867209.336608.png 1311867209.327422 depth/1311867209.327422.png
1311867209.368685 rgb/1311867209.368685.png 1311867209.358104 depth/1311867209.358104.png
1311867209.400674 rgb/1311867209.400674.png 1311867209.393797 depth/1311867209.393797.png
1311867209.436604 rgb/1311867209.436604.png 1311867209.425815 depth/1311867209.425815.png
1311867209.468504 rgb/1311867209.468504.png 1311867209.458133 depth/1311867209.458133.png
1311867209.501113 rgb/1311867209.501113.png 1311867209.494065 depth/1311867209.494065.png
1311867209.536902 rgb/1311867209.536902.png 1311867209.525873 depth/1311867209.525873.png
1311867209.568689 rgb/1311867209.568689.png 1311867209.558070 depth/1311867209.558070.png
1311867209.600759 rgb/1311867209.600759.png 1311867209.593954 depth/1311867209.593954.png
1311867209.636594 rgb/1311867209.636594.png 1311867209.626279 depth/1311867209.626279.png
1311867209.668570 rgb/1311867209.668570.png 1311867209.658202 depth/1311867209.658202.png
1311867209.701272 rgb/1311867209.701272.png 1311867209.696702 depth/1311867209.696702.png
1311867209.736573 rgb/1311867209.736573.png 1311867209.726264 depth/1311867209.726264.png
1311867209.768624 rgb/1311867209.768624.png 1311867209.758346 depth/1311867209.758346.png
1311867209.801498 rgb/1311867209.801498.png 1311867209.795932 depth/1311867209.795932.png
1311867209.836574 rgb/1311867209.836574.png 1311867209.826242 depth/1311867209.826242.png
1311867209.868553 rgb/1311867209.868553.png 1311867209.858896 depth/1311867209.858896.png
1311867209.900669 rgb/1311867209.900669.png 1311867209.894697 depth/1311867209.894697.png
1311867209.936544 rgb/1311867209.936544.png 1311867209.926845 depth/1311867209.926845.png
1311867209.968938 rgb/1311867209.968938.png 1311867209.958821 depth/1311867209.958821.png
1311867210.000704 rgb/1311867210.000704.png 1311867209.994254 depth/1311867209.994254.png
1311867210.036683 rgb/1311867210.036683.png 1311867210.026106 depth/1311867210.026106.png
1311867210.068816 rgb/1311867210.068816.png 1311867210.060359 depth/1311867210.060359.png
1311867210.100607 rgb/1311867210.100607.png 1311867210.094248 depth/1311867210.094248.png
1311867210.136711 rgb/1311867210.136711.png 1311867210.128034 depth/1311867210.128034.png
1311867210.168673 rgb/1311867210.168673.png 1311867210.157824 depth/1311867210.157824.png
1311867210.200662 rgb/1311867210.200662.png 1311867210.194321 depth/1311867210.194321.png
1311867210.236614 rgb/1311867210.236614.png 1311867210.225813 depth/1311867210.225813.png
1311867210.268764 rgb/1311867210.268764.png 1311867210.257977 depth/1311867210.257977.png
1311867210.300692 rgb/1311867210.300692.png 1311867210.295399 depth/1311867210.295399.png
1311867210.336672 rgb/1311867210.336672.png 1311867210.327137 depth/1311867210.327137.png
1311867210.368993 rgb/1311867210.368993.png 1311867210.358242 depth/1311867210.358242.png
1311867210.400741 rgb/1311867210.400741.png 1311867210.393792 depth/1311867210.393792.png
1311867210.436672 rgb/1311867210.436672.png 1311867210.426004 depth/1311867210.426004.png
1311867210.469063 rgb/1311867210.469063.png 1311867210.458171 depth/1311867210.458171.png
1311867210.500649 rgb/1311867210.500649.png 1311867210.494351 depth/1311867210.494351.png
1311867210.536682 rgb/1311867210.536682.png 1311867210.526130 depth/1311867210.526130.png
1311867210.569047 rgb/1311867210.569047.png 1311867210.563473 depth/1311867210.563473.png
1311867210.600859 rgb/1311867210.600859.png 1311867210.594387 depth/1311867210.594387.png
1311867210.636787 rgb/1311867210.636787.png 1311867210.626021 depth/1311867210.626021.png
1311867210.673847 rgb/1311867210.673847.png 1311867210.667571 depth/1311867210.667571.png
1311867210.700721 rgb/1311867210.700721.png 1311867210.695228 depth/1311867210.695228.png
1311867210.736657 rgb/1311867210.736657.png 1311867210.726090 depth/1311867210.726090.png
1311867210.769036 rgb/1311867210.769036.png 1311867210.762092 depth/1311867210.762092.png
1311867210.800700 rgb/1311867210.800700.png 1311867210.794349 depth/1311867210.794349.png
1311867210.836863 rgb/1311867210.836863.png 1311867210.826326 depth/1311867210.826326.png
1311867210.868831 rgb/1311867210.868831.png 1311867210.862398 depth/1311867210.862398.png
1311867210.900724 rgb/1311867210.900724.png 1311867210.894228 depth/1311867210.894228.png
1311867210.936751 rgb/1311867210.936751.png 1311867210.928831 depth/1311867210.928831.png
1311867210.969224 rgb/1311867210.969224.png 1311867210.965348 depth/1311867210.965348.png
1311867211.001198 rgb/1311867211.001198.png 1311867210.994558 depth/1311867210.994558.png
1311867211.036754 rgb/1311867211.036754.png 1311867211.026350 depth/1311867211.026350.png
1311867211.069171 rgb/1311867211.069171.png 1311867211.065157 depth/1311867211.065157.png
1311867211.101339 rgb/1311867211.101339.png 1311867211.094082 depth/1311867211.094082.png
1311867211.136879 rgb/1311867211.136879.png 1311867211.126688 depth/1311867211.126688.png
1311867211.169535 rgb/1311867211.169535.png 1311867211.164699 depth/1311867211.164699.png
1311867211.200759 rgb/1311867211.200759.png 1311867211.194663 depth/1311867211.194663.png
1311867211.236938 rgb/1311867211.236938.png 1311867211.227021 depth/1311867211.227021.png
1311867211.268944 rgb/1311867211.268944.png 1311867211.264560 depth/1311867211.264560.png
1311867211.301073 rgb/1311867211.301073.png 1311867211.295310 depth/1311867211.295310.png
1311867211.336815 rgb/1311867211.336815.png 1311867211.326295 depth/1311867211.326295.png
1311867211.368899 rgb/1311867211.368899.png 1311867211.365329 depth/1311867211.365329.png
1311867211.401155 rgb/1311867211.401155.png 1311867211.394902 depth/1311867211.394902.png
1311867211.436783 rgb/1311867211.436783.png 1311867211.429568 depth/1311867211.429568.png
1311867211.468760 rgb/1311867211.468760.png 1311867211.464506 depth/1311867211.464506.png
1311867211.500750 rgb/1311867211.500750.png 1311867211.494283 depth/1311867211.494283.png
1311867211.536921 rgb/1311867211.536921.png 1311867211.527957 depth/1311867211.527957.png
1311867211.569353 rgb/1311867211.569353.png 1311867211.564670 depth/1311867211.564670.png
1311867211.600936 rgb/1311867211.600936.png 1311867211.596759 depth/1311867211.596759.png
1311867211.636776 rgb/1311867211.636776.png 1311867211.626943 depth/1311867211.626943.png
1311867211.669417 rgb/1311867211.669417.png 1311867211.662028 depth/1311867211.662028.png
1311867211.700795 rgb/1311867211.700795.png 1311867211.694435 depth/1311867211.694435.png
1311867211.736761 rgb/1311867211.736761.png 1311867211.726757 depth/1311867211.726757.png
1311867211.769891 rgb/1311867211.769891.png 1311867211.764210 depth/1311867211.764210.png
1311867211.801052 rgb/1311867211.801052.png 1311867211.794816 depth/1311867211.794816.png
1311867211.838297 rgb/1311867211.838297.png 1311867211.833727 depth/1311867211.833727.png
1311867211.868798 rgb/1311867211.868798.png 1311867211.863093 depth/1311867211.863093.png
1311867211.901152 rgb/1311867211.901152.png 1311867211.896769 depth/1311867211.896769.png
1311867211.937348 rgb/1311867211.937348.png 1311867211.932430 depth/1311867211.932430.png
1311867211.971087 rgb/1311867211.971087.png 1311867211.965324 depth/1311867211.965324.png
1311867212.001054 rgb/1311867212.001054.png 1311867211.997286 depth/1311867211.997286.png
1311867212.037396 rgb/1311867212.037396.png 1311867212.031766 depth/1311867212.031766.png
1311867212.068925 rgb/1311867212.068925.png 1311867212.062152 depth/1311867212.062152.png
1311867212.100836 rgb/1311867212.100836.png 1311867212.095455 depth/1311867212.095455.png
1311867212.137104 rgb/1311867212.137104.png 1311867212.133103 depth/1311867212.133103.png
1311867212.168899 rgb/1311867212.168899.png 1311867212.166849 depth/1311867212.166849.png
1311867212.201292 rgb/1311867212.201292.png 1311867212.194507 depth/1311867212.194507.png
1311867212.236828 rgb/1311867212.236828.png 1311867212.230176 depth/1311867212.230176.png
1311867212.269660 rgb/1311867212.269660.png 1311867212.264719 depth/1311867212.264719.png
1311867212.300798 rgb/1311867212.300798.png 1311867212.294482 depth/1311867212.294482.png
1311867212.336980 rgb/1311867212.336980.png 1311867212.332643 depth/1311867212.332643.png
1311867212.369121 rgb/1311867212.369121.png 1311867212.365364 depth/1311867212.365364.png
1311867212.400874 rgb/1311867212.400874.png 1311867212.395551 depth/1311867212.395551.png
1311867212.437295 rgb/1311867212.437295.png 1311867212.432952 depth/1311867212.432952.png
1311867212.468814 rgb/1311867212.468814.png 1311867212.462264 depth/1311867212.462264.png
1311867212.500920 rgb/1311867212.500920.png 1311867212.494430 depth/1311867212.494430.png
1311867212.536991 rgb/1311867212.536991.png 1311867212.530027 depth/1311867212.530027.png
1311867212.568780 rgb/1311867212.568780.png 1311867212.562597 depth/1311867212.562597.png
1311867212.600775 rgb/1311867212.600775.png 1311867212.594836 depth/1311867212.594836.png
1311867212.636951 rgb/1311867212.636951.png 1311867212.632392 depth/1311867212.632392.png
1311867212.668874 rgb/1311867212.668874.png 1311867212.662983 depth/1311867212.662983.png
1311867212.701018 rgb/1311867212.701018.png 1311867212.694415 depth/1311867212.694415.png
1311867212.736989 rgb/1311867212.736989.png 1311867212.732322 depth/1311867212.732322.png
1311867212.768959 rgb/1311867212.768959.png 1311867212.761895 depth/1311867212.761895.png
1311867212.800808 rgb/1311867212.800808.png 1311867212.795161 depth/1311867212.795161.png
1311867212.837870 rgb/1311867212.837870.png 1311867212.830377 depth/1311867212.830377.png
1311867212.869033 rgb/1311867212.869033.png 1311867212.862524 depth/1311867212.862524.png
1311867212.900811 rgb/1311867212.900811.png 1311867212.894180 depth/1311867212.894180.png
1311867212.936948 rgb/1311867212.936948.png 1311867212.930659 depth/1311867212.930659.png
1311867212.969087 rgb/1311867212.969087.png 1311867212.962158 depth/1311867212.962158.png
1311867213.001064 rgb/1311867213.001064.png 1311867212.997198 depth/1311867212.997198.png
1311867213.036927 rgb/1311867213.036927.png 1311867213.030556 depth/1311867213.030556.png
1311867213.069051 rgb/1311867213.069051.png 1311867213.062233 depth/1311867213.062233.png
1311867213.101068 rgb/1311867213.101068.png 1311867213.098531 depth/1311867213.098531.png
1311867213.137000 rgb/1311867213.137000.png 1311867213.132167 depth/1311867213.132167.png
1311867213.169165 rgb/1311867213.169165.png 1311867213.164233 depth/1311867213.164233.png
1311867213.201431 rgb/1311867213.201431.png 1311867213.198165 depth/1311867213.198165.png
1311867213.236857 rgb/1311867213.236857.png 1311867213.230398 depth/1311867213.230398.png
1311867213.269223 rgb/1311867213.269223.png 1311867213.262134 depth/1311867213.262134.png
1311867213.301416 rgb/1311867213.301416.png 1311867213.298364 depth/1311867213.298364.png
1311867213.336896 rgb/1311867213.336896.png 1311867213.331297 depth/1311867213.331297.png
1311867213.369001 rgb/1311867213.369001.png 1311867213.362207 depth/1311867213.362207.png
1311867213.401378 rgb/1311867213.401378.png 1311867213.398062 depth/1311867213.398062.png
1311867213.437193 rgb/1311867213.437193.png 1311867213.430396 depth/1311867213.430396.png
1311867213.469040 rgb/1311867213.469040.png 1311867213.462063 depth/1311867213.462063.png
1311867213.500997 rgb/1311867213.500997.png 1311867213.498139 depth/1311867213.498139.png
1311867213.536881 rgb/1311867213.536881.png 1311867213.531834 depth/1311867213.531834.png
1311867213.569042 rgb/1311867213.569042.png 1311867213.562132 depth/1311867213.562132.png
1311867213.601011 rgb/1311867213.601011.png 1311867213.598958 depth/1311867213.598958.png
1311867213.636923 rgb/1311867213.636923.png 1311867213.632776 depth/1311867213.632776.png
1311867213.668995 rgb/1311867213.668995.png 1311867213.662325 depth/1311867213.662325.png
1311867213.701300 rgb/1311867213.701300.png 1311867213.698727 depth/1311867213.698727.png
1311867213.737146 rgb/1311867213.737146.png 1311867213.731280 depth/1311867213.731280.png
1311867213.769090 rgb/1311867213.769090.png 1311867213.762316 depth/1311867213.762316.png
1311867213.801664 rgb/1311867213.801664.png 1311867213.798497 depth/1311867213.798497.png
1311867213.837348 rgb/1311867213.837348.png 1311867213.830353 depth/1311867213.830353.png
1311867213.868914 rgb/1311867213.868914.png 1311867213.866938 depth/1311867213.866938.png
1311867213.900969 rgb/1311867213.900969.png 1311867213.898875 depth/1311867213.898875.png
1311867213.937067 rgb/1311867213.937067.png 1311867213.932459 depth/1311867213.932459.png
1311867213.968920 rgb/1311867213.968920.png 1311867213.962551 depth/1311867213.962551.png
1311867214.005161 rgb/1311867214.005161.png 1311867214.001499 depth/1311867214.001499.png
1311867214.037101 rgb/1311867214.037101.png 1311867214.031655 depth/1311867214.031655.png
1311867214.068910 rgb/1311867214.068910.png 1311867214.064003 depth/1311867214.064003.png
1311867214.104861 rgb/1311867214.104861.png 1311867214.098475 depth/1311867214.098475.png
1311867214.138206 rgb/1311867214.138206.png 1311867214.132699 depth/1311867214.132699.png
1311867214.169647 rgb/1311867214.169647.png 1311867214.164380 depth/1311867214.164380.png
1311867214.205217 rgb/1311867214.205217.png 1311867214.201302 depth/1311867214.201302.png
1311867214.239878 rgb/1311867214.239878.png 1311867214.233843 depth/1311867214.233843.png
1311867214.270552 rgb/1311867214.270552.png 1311867214.267490 depth/1311867214.267490.png
1311867214.305762 rgb/1311867214.305762.png 1311867214.300472 depth/1311867214.300472.png
1311867214.337669 rgb/1311867214.337669.png 1311867214.331055 depth/1311867214.331055.png
1311867214.369049 rgb/1311867214.369049.png 1311867214.366367 depth/1311867214.366367.png
1311867214.405033 rgb/1311867214.405033.png 1311867214.398003 depth/1311867214.398003.png
1311867214.437364 rgb/1311867214.437364.png 1311867214.433221 depth/1311867214.433221.png
1311867214.469778 rgb/1311867214.469778.png 1311867214.469818 depth/1311867214.469818.png
1311867214.505939 rgb/1311867214.505939.png 1311867214.500862 depth/1311867214.500862.png
1311867214.537369 rgb/1311867214.537369.png 1311867214.532909 depth/1311867214.532909.png
1311867214.569142 rgb/1311867214.569142.png 1311867214.566238 depth/1311867214.566238.png
1311867214.604864 rgb/1311867214.604864.png 1311867214.598216 depth/1311867214.598216.png
1311867214.636989 rgb/1311867214.636989.png 1311867214.630473 depth/1311867214.630473.png
1311867214.669101 rgb/1311867214.669101.png 1311867214.666559 depth/1311867214.666559.png
1311867214.704890 rgb/1311867214.704890.png 1311867214.698562 depth/1311867214.698562.png
1311867214.736964 rgb/1311867214.736964.png 1311867214.731080 depth/1311867214.731080.png
1311867214.769506 rgb/1311867214.769506.png 1311867214.768292 depth/1311867214.768292.png
1311867214.804993 rgb/1311867214.804993.png 1311867214.798063 depth/1311867214.798063.png
1311867214.836918 rgb/1311867214.836918.png 1311867214.830227 depth/1311867214.830227.png
1311867214.869998 rgb/1311867214.869998.png 1311867214.866509 depth/1311867214.866509.png
1311867214.904984 rgb/1311867214.904984.png 1311867214.898785 depth/1311867214.898785.png
1311867214.937253 rgb/1311867214.937253.png 1311867214.930825 depth/1311867214.930825.png
1311867214.969304 rgb/1311867214.969304.png 1311867214.966350 depth/1311867214.966350.png
1311867215.005064 rgb/1311867215.005064.png 1311867214.998091 depth/1311867214.998091.png
1311867215.037107 rgb/1311867215.037107.png 1311867215.030535 depth/1311867215.030535.png
1311867215.069291 rgb/1311867215.069291.png 1311867215.066838 depth/1311867215.066838.png
1311867215.105004 rgb/1311867215.105004.png 1311867215.098625 depth/1311867215.098625.png
1311867215.136914 rgb/1311867215.136914.png 1311867215.130449 depth/1311867215.130449.png
1311867215.169446 rgb/1311867215.169446.png 1311867215.166475 depth/1311867215.166475.png
1311867215.204946 rgb/1311867215.204946.png 1311867215.198166 depth/1311867215.198166.png
1311867215.236951 rgb/1311867215.236951.png 1311867215.230539 depth/1311867215.230539.png
1311867215.269082 rgb/1311867215.269082.png 1311867215.267247 depth/1311867215.267247.png
1311867215.304957 rgb/1311867215.304957.png 1311867215.298450 depth/1311867215.298450.png
1311867215.336962 rgb/1311867215.336962.png 1311867215.330815 depth/1311867215.330815.png
1311867215.369184 rgb/1311867215.369184.png 1311867215.366868 depth/1311867215.366868.png
1311867215.404952 rgb/1311867215.404952.png 1311867215.398538 depth/1311867215.398538.png
1311867215.437035 rgb/1311867215.437035.png 1311867215.430540 depth/1311867215.430540.png
1311867215.469090 rgb/1311867215.469090.png 1311867215.466565 depth/1311867215.466565.png
1311867215.504980 rgb/1311867215.504980.png 1311867215.498574 depth/1311867215.498574.png
1311867215.537123 rgb/1311867215.537123.png 1311867215.534556 depth/1311867215.534556.png
1311867215.569034 rgb/1311867215.569034.png 1311867215.566537 depth/1311867215.566537.png
1311867215.605085 rgb/1311867215.605085.png 1311867215.599212 depth/1311867215.599212.png
1311867215.637055 rgb/1311867215.637055.png 1311867215.634636 depth/1311867215.634636.png
1311867215.668922 rgb/1311867215.668922.png 1311867215.667807 depth/1311867215.667807.png
1311867215.704951 rgb/1311867215.704951.png 1311867215.698918 depth/1311867215.698918.png
1311867215.738883 rgb/1311867215.738883.png 1311867215.736307 depth/1311867215.736307.png
1311867215.769199 rgb/1311867215.769199.png 1311867215.767234 depth/1311867215.767234.png
1311867215.804883 rgb/1311867215.804883.png 1311867215.798475 depth/1311867215.798475.png
1311867215.837335 rgb/1311867215.837335.png 1311867215.834626 depth/1311867215.834626.png
1311867215.869167 rgb/1311867215.869167.png 1311867215.867785 depth/1311867215.867785.png
1311867215.905276 rgb/1311867215.905276.png 1311867215.901509 depth/1311867215.901509.png
1311867215.937088 rgb/1311867215.937088.png 1311867215.936341 depth/1311867215.936341.png
1311867215.970287 rgb/1311867215.970287.png 1311867215.967170 depth/1311867215.967170.png
1311867216.005079 rgb/1311867216.005079.png 1311867215.998861 depth/1311867215.998861.png
1311867216.036968 rgb/1311867216.036968.png 1311867216.036000 depth/1311867216.036000.png
1311867216.069483 rgb/1311867216.069483.png 1311867216.066615 depth/1311867216.066615.png
1311867216.105043 rgb/1311867216.105043.png 1311867216.098439 depth/1311867216.098439.png
1311867216.139295 rgb/1311867216.139295.png 1311867216.135610 depth/1311867216.135610.png
1311867216.169209 rgb/1311867216.169209.png 1311867216.169219 depth/1311867216.169219.png
1311867216.204961 rgb/1311867216.204961.png 1311867216.198337 depth/1311867216.198337.png
1311867216.237023 rgb/1311867216.237023.png 1311867216.235626 depth/1311867216.235626.png
1311867216.270663 rgb/1311867216.270663.png 1311867216.266688 depth/1311867216.266688.png
1311867216.305048 rgb/1311867216.305048.png 1311867216.298872 depth/1311867216.298872.png
1311867216.339542 rgb/1311867216.339542.png 1311867216.337480 depth/1311867216.337480.png
1311867216.369469 rgb/1311867216.369469.png 1311867216.366949 depth/1311867216.366949.png
1311867216.405512 rgb/1311867216.405512.png 1311867216.398915 depth/1311867216.398915.png
1311867216.437341 rgb/1311867216.437341.png 1311867216.435030 depth/1311867216.435030.png
1311867216.469753 rgb/1311867216.469753.png 1311867216.467146 depth/1311867216.467146.png
1311867216.504980 rgb/1311867216.504980.png 1311867216.499518 depth/1311867216.499518.png
1311867216.537226 rgb/1311867216.537226.png 1311867216.537110 depth/1311867216.537110.png
1311867216.569333 rgb/1311867216.569333.png 1311867216.566721 depth/1311867216.566721.png
1311867216.605032 rgb/1311867216.605032.png 1311867216.599049 depth/1311867216.599049.png
1311867216.637314 rgb/1311867216.637314.png 1311867216.637349 depth/1311867216.637349.png
1311867216.669119 rgb/1311867216.669119.png 1311867216.666770 depth/1311867216.666770.png
1311867216.705236 rgb/1311867216.705236.png 1311867216.698460 depth/1311867216.698460.png
1311867216.737208 rgb/1311867216.737208.png 1311867216.735234 depth/1311867216.735234.png
1311867216.769195 rgb/1311867216.769195.png 1311867216.766676 depth/1311867216.766676.png
1311867216.805002 rgb/1311867216.805002.png 1311867216.804141 depth/1311867216.804141.png
1311867216.837963 rgb/1311867216.837963.png 1311867216.834647 depth/1311867216.834647.png
1311867216.870340 rgb/1311867216.870340.png 1311867216.866658 depth/1311867216.866658.png
1311867216.904959 rgb/1311867216.904959.png 1311867216.904330 depth/1311867216.904330.png
1311867216.937407 rgb/1311867216.937407.png 1311867216.934638 depth/1311867216.934638.png
1311867216.969173 rgb/1311867216.969173.png 1311867216.967064 depth/1311867216.967064.png
1311867217.005327 rgb/1311867217.005327.png 1311867217.003467 depth/1311867217.003467.png
1311867217.037311 rgb/1311867217.037311.png 1311867217.034613 depth/1311867217.034613.png
1311867217.069129 rgb/1311867217.069129.png 1311867217.066936 depth/1311867217.066936.png
1311867217.105258 rgb/1311867217.105258.png 1311867217.104641 depth/1311867217.104641.png
1311867217.137085 rgb/1311867217.137085.png 1311867217.136313 depth/1311867217.136313.png
1311867217.169189 rgb/1311867217.169189.png 1311867217.166641 depth/1311867217.166641.png
1311867217.205792 rgb/1311867217.205792.png 1311867217.202562 depth/1311867217.202562.png
1311867217.237168 rgb/1311867217.237168.png 1311867217.234561 depth/1311867217.234561.png
1311867217.269228 rgb/1311867217.269228.png 1311867217.266687 depth/1311867217.266687.png
1311867217.305164 rgb/1311867217.305164.png 1311867217.303071 depth/1311867217.303071.png
1311867217.337405 rgb/1311867217.337405.png 1311867217.335057 depth/1311867217.335057.png
1311867217.369597 rgb/1311867217.369597.png 1311867217.367254 depth/1311867217.367254.png
1311867217.412045 rgb/1311867217.412045.png 1311867217.405199 depth/1311867217.405199.png
1311867217.437282 rgb/1311867217.437282.png 1311867217.435256 depth/1311867217.435256.png
1311867217.469419 rgb/1311867217.469419.png 1311867217.469430 depth/1311867217.469430.png
1311867217.505032 rgb/1311867217.505032.png 1311867217.505043 depth/1311867217.505043.png
1311867217.537068 rgb/1311867217.537068.png 1311867217.534680 depth/1311867217.534680.png
1311867217.569154 rgb/1311867217.569154.png 1311867217.566950 depth/1311867217.566950.png
1311867217.605054 rgb/1311867217.605054.png 1311867217.602982 depth/1311867217.602982.png
1311867217.637099 rgb/1311867217.637099.png 1311867217.634689 depth/1311867217.634689.png
1311867217.669100 rgb/1311867217.669100.png 1311867217.666971 depth/1311867217.666971.png
1311867217.705063 rgb/1311867217.705063.png 1311867217.704535 depth/1311867217.704535.png
1311867217.737154 rgb/1311867217.737154.png 1311867217.735349 depth/1311867217.735349.png
1311867217.769488 rgb/1311867217.769488.png 1311867217.767069 depth/1311867217.767069.png
1311867217.805184 rgb/1311867217.805184.png 1311867217.802824 depth/1311867217.802824.png
1311867217.837227 rgb/1311867217.837227.png 1311867217.835056 depth/1311867217.835056.png
1311867217.869085 rgb/1311867217.869085.png 1311867217.867660 depth/1311867217.867660.png
1311867217.905635 rgb/1311867217.905635.png 1311867217.903143 depth/1311867217.903143.png
1311867217.937258 rgb/1311867217.937258.png 1311867217.935124 depth/1311867217.935124.png
1311867217.971093 rgb/1311867217.971093.png 1311867217.971100 depth/1311867217.971100.png
1311867218.005224 rgb/1311867218.005224.png 1311867218.003978 depth/1311867218.003978.png
1311867218.037144 rgb/1311867218.037144.png 1311867218.034727 depth/1311867218.034727.png
1311867218.071085 rgb/1311867218.071085.png 1311867218.071095 depth/1311867218.071095.png
1311867218.105098 rgb/1311867218.105098.png 1311867218.102904 depth/1311867218.102904.png
1311867218.137118 rgb/1311867218.137118.png 1311867218.135394 depth/1311867218.135394.png
1311867218.171201 rgb/1311867218.171201.png 1311867218.171209 depth/1311867218.171209.png
1311867218.205035 rgb/1311867218.205035.png 1311867218.204112 depth/1311867218.204112.png
1311867218.237244 rgb/1311867218.237244.png 1311867218.235236 depth/1311867218.235236.png
1311867218.271553 rgb/1311867218.271553.png 1311867218.271564 depth/1311867218.271564.png
1311867218.305133 rgb/1311867218.305133.png 1311867218.303010 depth/1311867218.303010.png
1311867218.337365 rgb/1311867218.337365.png 1311867218.335330 depth/1311867218.335330.png
1311867218.373471 rgb/1311867218.373471.png 1311867218.373477 depth/1311867218.373477.png
1311867218.405269 rgb/1311867218.405269.png 1311867218.403041 depth/1311867218.403041.png
1311867218.437232 rgb/1311867218.437232.png 1311867218.435479 depth/1311867218.435479.png
1311867218.472952 rgb/1311867218.472952.png 1311867218.472975 depth/1311867218.472975.png
1311867218.505117 rgb/1311867218.505117.png 1311867218.503413 depth/1311867218.503413.png
1311867218.537273 rgb/1311867218.537273.png 1311867218.535025 depth/1311867218.535025.png
1311867218.571458 rgb/1311867218.571458.png 1311867218.571476 depth/1311867218.571476.png
1311867218.605932 rgb/1311867218.605932.png 1311867218.602762 depth/1311867218.602762.png
1311867218.637202 rgb/1311867218.637202.png 1311867218.636531 depth/1311867218.636531.png
1311867218.671051 rgb/1311867218.671051.png 1311867218.671082 depth/1311867218.671082.png
1311867218.705900 rgb/1311867218.705900.png 1311867218.702733 depth/1311867218.702733.png
1311867218.737849 rgb/1311867218.737849.png 1311867218.735286 depth/1311867218.735286.png
1311867218.771585 rgb/1311867218.771585.png 1311867218.771590 depth/1311867218.771590.png
1311867218.805242 rgb/1311867218.805242.png 1311867218.802779 depth/1311867218.802779.png
1311867218.837996 rgb/1311867218.837996.png 1311867218.834796 depth/1311867218.834796.png
1311867218.872727 rgb/1311867218.872727.png 1311867218.872734 depth/1311867218.872734.png
1311867218.905486 rgb/1311867218.905486.png 1311867218.902682 depth/1311867218.902682.png
1311867218.937220 rgb/1311867218.937220.png 1311867218.935555 depth/1311867218.935555.png
1311867218.973161 rgb/1311867218.973161.png 1311867218.973168 depth/1311867218.973168.png
1311867219.005183 rgb/1311867219.005183.png 1311867219.003058 depth/1311867219.003058.png
1311867219.037124 rgb/1311867219.037124.png 1311867219.035078 depth/1311867219.035078.png
1311867219.073837 rgb/1311867219.073837.png 1311867219.073843 depth/1311867219.073843.png
1311867219.105080 rgb/1311867219.105080.png 1311867219.102872 depth/1311867219.102872.png
1311867219.138326 rgb/1311867219.138326.png 1311867219.135339 depth/1311867219.135339.png
1311867219.170841 rgb/1311867219.170841.png 1311867219.170846 depth/1311867219.170846.png
1311867219.205245 rgb/1311867219.205245.png 1311867219.202940 depth/1311867219.202940.png
1311867219.239134 rgb/1311867219.239134.png 1311867219.239013 depth/1311867219.239013.png
1311867219.270902 rgb/1311867219.270902.png 1311867219.270906 depth/1311867219.270906.png
1311867219.305243 rgb/1311867219.305243.png 1311867219.303487 depth/1311867219.303487.png
1311867219.340155 rgb/1311867219.340155.png 1311867219.340160 depth/1311867219.340160.png
1311867219.371495 rgb/1311867219.371495.png 1311867219.371505 depth/1311867219.371505.png
1311867219.405197 rgb/1311867219.405197.png 1311867219.403433 depth/1311867219.403433.png
1311867219.439479 rgb/1311867219.439479.png 1311867219.439486 depth/1311867219.439486.png
1311867219.471709 rgb/1311867219.471709.png 1311867219.471730 depth/1311867219.471730.png
1311867219.505156 rgb/1311867219.505156.png 1311867219.503311 depth/1311867219.503311.png
1311867219.539180 rgb/1311867219.539180.png 1311867219.539195 depth/1311867219.539195.png
1311867219.574333 rgb/1311867219.574333.png 1311867219.574347 depth/1311867219.574347.png
1311867219.608604 rgb/1311867219.608604.png 1311867219.608626 depth/1311867219.608626.png
1311867219.642360 rgb/1311867219.642360.png 1311867219.642502 depth/1311867219.642502.png
1311867219.671103 rgb/1311867219.671103.png 1311867219.671117 depth/1311867219.671117.png
1311867219.705287 rgb/1311867219.705287.png 1311867219.702987 depth/1311867219.702987.png
1311867219.739499 rgb/1311867219.739499.png 1311867219.739518 depth/1311867219.739518.png
1311867219.773963 rgb/1311867219.773963.png 1311867219.777211 depth/1311867219.777211.png
1311867219.805177 rgb/1311867219.805177.png 1311867219.803964 depth/1311867219.803964.png
1311867219.839721 rgb/1311867219.839721.png 1311867219.839734 depth/1311867219.839734.png
1311867219.875308 rgb/1311867219.875308.png 1311867219.875322 depth/1311867219.875322.png
1311867219.910839 rgb/1311867219.910839.png 1311867219.907134 depth/1311867219.907134.png
1311867219.941763 rgb/1311867219.941763.png 1311867219.941782 depth/1311867219.941782.png
1311867219.973219 rgb/1311867219.973219.png 1311867219.973230 depth/1311867219.973230.png
1311867220.006868 rgb/1311867220.006868.png 1311867220.006463 depth/1311867220.006463.png
1311867220.042194 rgb/1311867220.042194.png 1311867220.042243 depth/1311867220.042243.png
1311867220.074365 rgb/1311867220.074365.png 1311867220.074382 depth/1311867220.074382.png
1311867220.105276 rgb/1311867220.105276.png 1311867220.103671 depth/1311867220.103671.png
1311867220.142093 rgb/1311867220.142093.png 1311867220.142123 depth/1311867220.142123.png
1311867220.171409 rgb/1311867220.171409.png 1311867220.171473 depth/1311867220.171473.png
1311867220.206177 rgb/1311867220.206177.png 1311867220.206199 depth/1311867220.206199.png
1311867220.242193 rgb/1311867220.242193.png 1311867220.242225 depth/1311867220.242225.png
1311867220.274111 rgb/1311867220.274111.png 1311867220.274128 depth/1311867220.274128.png
1311867220.306449 rgb/1311867220.306449.png 1311867220.306458 depth/1311867220.306458.png
1311867220.342053 rgb/1311867220.342053.png 1311867220.342100 depth/1311867220.342100.png
1311867220.371471 rgb/1311867220.371471.png 1311867220.371487 depth/1311867220.371487.png
1311867220.406370 rgb/1311867220.406370.png 1311867220.406380 depth/1311867220.406380.png
1311867220.440877 rgb/1311867220.440877.png 1311867220.440884 depth/1311867220.440884.png
1311867220.472868 rgb/1311867220.472868.png 1311867220.472875 depth/1311867220.472875.png
1311867220.509080 rgb/1311867220.509080.png 1311867220.509106 depth/1311867220.509106.png
1311867220.541975 rgb/1311867220.541975.png 1311867220.541985 depth/1311867220.541985.png
1311867220.571621 rgb/1311867220.571621.png 1311867220.571640 depth/1311867220.571640.png
1311867220.610419 rgb/1311867220.610419.png 1311867220.610425 depth/1311867220.610425.png
1311867220.639667 rgb/1311867220.639667.png 1311867220.641550 depth/1311867220.641550.png
1311867220.671279 rgb/1311867220.671279.png 1311867220.671309 depth/1311867220.671309.png
1311867220.707327 rgb/1311867220.707327.png 1311867220.707336 depth/1311867220.707336.png
1311867220.739338 rgb/1311867220.739338.png 1311867220.739344 depth/1311867220.739344.png
1311867220.771914 rgb/1311867220.771914.png 1311867220.771985 depth/1311867220.771985.png
1311867220.809727 rgb/1311867220.809727.png 1311867220.809753 depth/1311867220.809753.png
1311867220.841417 rgb/1311867220.841417.png 1311867220.841502 depth/1311867220.841502.png
1311867220.871240 rgb/1311867220.871240.png 1311867220.871248 depth/1311867220.871248.png
1311867220.907590 rgb/1311867220.907590.png 1311867220.907596 depth/1311867220.907596.png
1311867220.939280 rgb/1311867220.939280.png 1311867220.939297 depth/1311867220.939297.png
1311867220.971313 rgb/1311867220.971313.png 1311867220.971319 depth/1311867220.971319.png
1311867221.008955 rgb/1311867221.008955.png 1311867221.009018 depth/1311867221.009018.png
1311867221.039288 rgb/1311867221.039288.png 1311867221.039294 depth/1311867221.039294.png
1311867221.072099 rgb/1311867221.072099.png 1311867221.071571 depth/1311867221.071571.png
1311867221.107750 rgb/1311867221.107750.png 1311867221.107758 depth/1311867221.107758.png
1311867221.139766 rgb/1311867221.139766.png 1311867221.139779 depth/1311867221.139779.png
1311867221.171684 rgb/1311867221.171684.png 1311867221.171691 depth/1311867221.171691.png
1311867221.208397 rgb/1311867221.208397.png 1311867221.208183 depth/1311867221.208183.png
1311867221.239750 rgb/1311867221.239750.png 1311867221.239813 depth/1311867221.239813.png
1311867221.271980 rgb/1311867221.271980.png 1311867221.272124 depth/1311867221.272124.png
1311867221.307576 rgb/1311867221.307576.png 1311867221.307593 depth/1311867221.307593.png
1311867221.339333 rgb/1311867221.339333.png 1311867221.339345 depth/1311867221.339345.png
1311867221.371416 rgb/1311867221.371416.png 1311867221.371422 depth/1311867221.371422.png
1311867221.407147 rgb/1311867221.407147.png 1311867221.407388 depth/1311867221.407388.png
1311867221.440006 rgb/1311867221.440006.png 1311867221.440068 depth/1311867221.440068.png
1311867221.471228 rgb/1311867221.471228.png 1311867221.471241 depth/1311867221.471241.png
1311867221.508153 rgb/1311867221.508153.png 1311867221.508172 depth/1311867221.508172.png
1311867221.539675 rgb/1311867221.539675.png 1311867221.539691 depth/1311867221.539691.png
1311867221.571272 rgb/1311867221.571272.png 1311867221.571279 depth/1311867221.571279.png
1311867221.607168 rgb/1311867221.607168.png 1311867221.607311 depth/1311867221.607311.png
1311867221.640370 rgb/1311867221.640370.png 1311867221.640377 depth/1311867221.640377.png
1311867221.669453 rgb/1311867221.669453.png 1311867221.677148 depth/1311867221.677148.png
1311867221.707171 rgb/1311867221.707171.png 1311867221.707202 depth/1311867221.707202.png
1311867221.742382 rgb/1311867221.742382.png 1311867221.742393 depth/1311867221.742393.png
1311867221.769386 rgb/1311867221.769386.png 1311867221.777350 depth/1311867221.777350.png
1311867221.807422 rgb/1311867221.807422.png 1311867221.807454 depth/1311867221.807454.png
1311867221.839645 rgb/1311867221.839645.png 1311867221.839652 depth/1311867221.839652.png
1311867221.869580 rgb/1311867221.869580.png 1311867221.877733 depth/1311867221.877733.png
1311867221.907739 rgb/1311867221.907739.png 1311867221.907749 depth/1311867221.907749.png
1311867221.942361 rgb/1311867221.942361.png 1311867221.942463 depth/1311867221.942463.png
1311867221.969578 rgb/1311867221.969578.png 1311867221.977536 depth/1311867221.977536.png
1311867222.009006 rgb/1311867222.009006.png 1311867222.008677 depth/1311867222.008677.png
1311867222.042876 rgb/1311867222.042876.png 1311867222.039534 depth/1311867222.039534.png
1311867222.069362 rgb/1311867222.069362.png 1311867222.078253 depth/1311867222.078253.png
1311867222.111094 rgb/1311867222.111094.png 1311867222.107797 depth/1311867222.107797.png
1311867222.140683 rgb/1311867222.140683.png 1311867222.140690 depth/1311867222.140690.png
1311867222.169399 rgb/1311867222.169399.png 1311867222.179799 depth/1311867222.179799.png
1311867222.208160 rgb/1311867222.208160.png 1311867222.208173 depth/1311867222.208173.png
1311867222.240073 rgb/1311867222.240073.png 1311867222.240084 depth/1311867222.240084.png
1311867222.269681 rgb/1311867222.269681.png 1311867222.276030 depth/1311867222.276030.png
1311867222.307736 rgb/1311867222.307736.png 1311867222.307742 depth/1311867222.307742.png
1311867222.339630 rgb/1311867222.339630.png 1311867222.339639 depth/1311867222.339639.png
1311867222.369496 rgb/1311867222.369496.png 1311867222.379236 depth/1311867222.379236.png
1311867222.410190 rgb/1311867222.410190.png 1311867222.410200 depth/1311867222.410200.png
1311867222.443636 rgb/1311867222.443636.png 1311867222.443643 depth/1311867222.443643.png
1311867222.469409 rgb/1311867222.469409.png 1311867222.478112 depth/1311867222.478112.png
1311867222.508688 rgb/1311867222.508688.png 1311867222.508709 depth/1311867222.508709.png
1311867222.540167 rgb/1311867222.540167.png 1311867222.540179 depth/1311867222.540179.png
1311867222.569671 rgb/1311867222.569671.png 1311867222.577404 depth/1311867222.577404.png
1311867222.608424 rgb/1311867222.608424.png 1311867222.608439 depth/1311867222.608439.png
1311867222.643296 rgb/1311867222.643296.png 1311867222.643312 depth/1311867222.643312.png
1311867222.669574 rgb/1311867222.669574.png 1311867222.679649 depth/1311867222.679649.png
1311867222.708011 rgb/1311867222.708011.png 1311867222.708025 depth/1311867222.708025.png
1311867222.739992 rgb/1311867222.739992.png 1311867222.740008 depth/1311867222.740008.png
1311867222.769457 rgb/1311867222.769457.png 1311867222.779394 depth/1311867222.779394.png
1311867222.809321 rgb/1311867222.809321.png 1311867222.809157 depth/1311867222.809157.png
1311867222.840258 rgb/1311867222.840258.png 1311867222.840276 depth/1311867222.840276.png
1311867222.869499 rgb/1311867222.869499.png 1311867222.881298 depth/1311867222.881298.png
1311867222.908232 rgb/1311867222.908232.png 1311867222.908236 depth/1311867222.908236.png
1311867222.937591 rgb/1311867222.937591.png 1311867222.947082 depth/1311867222.947082.png
1311867222.969488 rgb/1311867222.969488.png 1311867222.983102 depth/1311867222.983102.png
1311867223.007824 rgb/1311867223.007824.png 1311867223.007831 depth/1311867223.007831.png
1311867223.037495 rgb/1311867223.037495.png 1311867223.045406 depth/1311867223.045406.png
1311867223.069417 rgb/1311867223.069417.png 1311867223.080825 depth/1311867223.080825.png
1311867223.109412 rgb/1311867223.109412.png 1311867223.109423 depth/1311867223.109423.png
1311867223.138136 rgb/1311867223.138136.png 1311867223.147377 depth/1311867223.147377.png
1311867223.175852 rgb/1311867223.175852.png 1311867223.175858 depth/1311867223.175858.png
1311867223.208002 rgb/1311867223.208002.png 1311867223.207819 depth/1311867223.207819.png
1311867223.237463 rgb/1311867223.237463.png 1311867223.245008 depth/1311867223.245008.png
1311867223.277936 rgb/1311867223.277936.png 1311867223.276362 depth/1311867223.276362.png
1311867223.308589 rgb/1311867223.308589.png 1311867223.308600 depth/1311867223.308600.png
1311867223.337625 rgb/1311867223.337625.png 1311867223.345242 depth/1311867223.345242.png
1311867223.375432 rgb/1311867223.375432.png 1311867223.379469 depth/1311867223.379469.png
1311867223.407361 rgb/1311867223.407361.png 1311867223.407424 depth/1311867223.407424.png
1311867223.437562 rgb/1311867223.437562.png 1311867223.445800 depth/1311867223.445800.png
1311867223.475825 rgb/1311867223.475825.png 1311867223.475833 depth/1311867223.475833.png
1311867223.507732 rgb/1311867223.507732.png 1311867223.507743 depth/1311867223.507743.png
1311867223.537550 rgb/1311867223.537550.png 1311867223.546653 depth/1311867223.546653.png
1311867223.575919 rgb/1311867223.575919.png 1311867223.575954 depth/1311867223.575954.png
1311867223.607790 rgb/1311867223.607790.png 1311867223.607807 depth/1311867223.607807.png
1311867223.637449 rgb/1311867223.637449.png 1311867223.650204 depth/1311867223.650204.png
1311867223.675382 rgb/1311867223.675382.png 1311867223.675388 depth/1311867223.675388.png
1311867223.708839 rgb/1311867223.708839.png 1311867223.708858 depth/1311867223.708858.png
1311867223.737594 rgb/1311867223.737594.png 1311867223.745281 depth/1311867223.745281.png
1311867223.776066 rgb/1311867223.776066.png 1311867223.776072 depth/1311867223.776072.png
1311867223.807750 rgb/1311867223.807750.png 1311867223.807756 depth/1311867223.807756.png
1311867223.837481 rgb/1311867223.837481.png 1311867223.843852 depth/1311867223.843852.png
1311867223.876077 rgb/1311867223.876077.png 1311867223.876092 depth/1311867223.876092.png
1311867223.907813 rgb/1311867223.907813.png 1311867223.907828 depth/1311867223.907828.png
1311867223.938926 rgb/1311867223.938926.png 1311867223.949167 depth/1311867223.949167.png
1311867223.976047 rgb/1311867223.976047.png 1311867223.976074 depth/1311867223.976074.png
1311867224.009213 rgb/1311867224.009213.png 1311867224.009344 depth/1311867224.009344.png
1311867224.037596 rgb/1311867224.037596.png 1311867224.047044 depth/1311867224.047044.png
1311867224.076133 rgb/1311867224.076133.png 1311867224.076141 depth/1311867224.076141.png
1311867224.108128 rgb/1311867224.108128.png 1311867224.108135 depth/1311867224.108135.png
1311867224.137526 rgb/1311867224.137526.png 1311867224.145899 depth/1311867224.145899.png
1311867224.176888 rgb/1311867224.176888.png 1311867224.176893 depth/1311867224.176893.png
1311867224.205512 rgb/1311867224.205512.png 1311867224.214377 depth/1311867224.214377.png
1311867224.237792 rgb/1311867224.237792.png 1311867224.247043 depth/1311867224.247043.png
1311867224.276855 rgb/1311867224.276855.png 1311867224.276863 depth/1311867224.276863.png
1311867224.305465 rgb/1311867224.305465.png 1311867224.314617 depth/1311867224.314617.png
1311867224.337546 rgb/1311867224.337546.png 1311867224.345673 depth/1311867224.345673.png
1311867224.376913 rgb/1311867224.376913.png 1311867224.376921 depth/1311867224.376921.png
1311867224.405603 rgb/1311867224.405603.png 1311867224.414102 depth/1311867224.414102.png
1311867224.437516 rgb/1311867224.437516.png 1311867224.446427 depth/1311867224.446427.png
1311867224.477686 rgb/1311867224.477686.png 1311867224.477419 depth/1311867224.477419.png
1311867224.505660 rgb/1311867224.505660.png 1311867224.518122 depth/1311867224.518122.png
1311867224.537809 rgb/1311867224.537809.png 1311867224.547057 depth/1311867224.547057.png
1311867224.585912 rgb/1311867224.585912.png 1311867224.580686 depth/1311867224.580686.png
1311867224.605597 rgb/1311867224.605597.png 1311867224.618112 depth/1311867224.618112.png
1311867224.637806 rgb/1311867224.637806.png 1311867224.650216 depth/1311867224.650216.png
1311867224.678501 rgb/1311867224.678501.png 1311867224.678519 depth/1311867224.678519.png
1311867224.705493 rgb/1311867224.705493.png 1311867224.717365 depth/1311867224.717365.png
1311867224.737612 rgb/1311867224.737612.png 1311867224.752092 depth/1311867224.752092.png
1311867224.786626 rgb/1311867224.786626.png 1311867224.781324 depth/1311867224.781324.png
1311867224.805654 rgb/1311867224.805654.png 1311867224.812346 depth/1311867224.812346.png
1311867224.837824 rgb/1311867224.837824.png 1311867224.845819 depth/1311867224.845819.png
1311867224.877943 rgb/1311867224.877943.png 1311867224.877666 depth/1311867224.877666.png
1311867224.905651 rgb/1311867224.905651.png 1311867224.914245 depth/1311867224.914245.png
1311867224.937570 rgb/1311867224.937570.png 1311867224.947145 depth/1311867224.947145.png
1311867224.979735 rgb/1311867224.979735.png 1311867224.980049 depth/1311867224.980049.png
1311867225.006618 rgb/1311867225.006618.png 1311867225.014292 depth/1311867225.014292.png
1311867225.037681 rgb/1311867225.037681.png 1311867225.049388 depth/1311867225.049388.png
1311867225.079869 rgb/1311867225.079869.png 1311867225.079540 depth/1311867225.079540.png
1311867225.105549 rgb/1311867225.105549.png 1311867225.113819 depth/1311867225.113819.png
1311867225.137763 rgb/1311867225.137763.png 1311867225.147238 depth/1311867225.147238.png
1311867225.180820 rgb/1311867225.180820.png 1311867225.181094 depth/1311867225.181094.png
1311867225.205557 rgb/1311867225.205557.png 1311867225.215322 depth/1311867225.215322.png
1311867225.237668 rgb/1311867225.237668.png 1311867225.248347 depth/1311867225.248347.png
1311867225.279255 rgb/1311867225.279255.png 1311867225.279291 depth/1311867225.279291.png
1311867225.305777 rgb/1311867225.305777.png 1311867225.320754 depth/1311867225.320754.png
1311867225.337676 rgb/1311867225.337676.png 1311867225.346235 depth/1311867225.346235.png
1311867225.373693 rgb/1311867225.373693.png 1311867225.385207 depth/1311867225.385207.png
1311867225.405582 rgb/1311867225.405582.png 1311867225.413013 depth/1311867225.413013.png
1311867225.437602 rgb/1311867225.437602.png 1311867225.450427 depth/1311867225.450427.png
1311867225.473714 rgb/1311867225.473714.png 1311867225.484295 depth/1311867225.484295.png
1311867225.505610 rgb/1311867225.505610.png 1311867225.516392 depth/1311867225.516392.png
1311867225.537795 rgb/1311867225.537795.png 1311867225.549375 depth/1311867225.549375.png
1311867225.573788 rgb/1311867225.573788.png 1311867225.588235 depth/1311867225.588235.png
1311867225.605520 rgb/1311867225.605520.png 1311867225.617901 depth/1311867225.617901.png
1311867225.637625 rgb/1311867225.637625.png 1311867225.646129 depth/1311867225.646129.png
1311867225.673806 rgb/1311867225.673806.png 1311867225.684712 depth/1311867225.684712.png
1311867225.705642 rgb/1311867225.705642.png 1311867225.716077 depth/1311867225.716077.png
1311867225.737747 rgb/1311867225.737747.png 1311867225.750630 depth/1311867225.750630.png
1311867225.773659 rgb/1311867225.773659.png 1311867225.787290 depth/1311867225.787290.png
1311867225.805618 rgb/1311867225.805618.png 1311867225.817078 depth/1311867225.817078.png
1311867225.837804 rgb/1311867225.837804.png 1311867225.852002 depth/1311867225.852002.png
1311867225.873778 rgb/1311867225.873778.png 1311867225.886291 depth/1311867225.886291.png
1311867225.905632 rgb/1311867225.905632.png 1311867225.917793 depth/1311867225.917793.png
1311867225.937904 rgb/1311867225.937904.png 1311867225.950491 depth/1311867225.950491.png
1311867225.973591 rgb/1311867225.973591.png 1311867225.985248 depth/1311867225.985248.png
1311867226.005870 rgb/1311867226.005870.png 1311867226.017372 depth/1311867226.017372.png
1311867226.037807 rgb/1311867226.037807.png 1311867226.051148 depth/1311867226.051148.png
1311867226.073737 rgb/1311867226.073737.png 1311867226.087782 depth/1311867226.087782.png
1311867226.105587 rgb/1311867226.105587.png 1311867226.118227 depth/1311867226.118227.png
1311867226.137702 rgb/1311867226.137702.png 1311867226.147749 depth/1311867226.147749.png
1311867226.173782 rgb/1311867226.173782.png 1311867226.183314 depth/1311867226.183314.png
1311867226.205652 rgb/1311867226.205652.png 1311867226.216681 depth/1311867226.216681.png
1311867226.237839 rgb/1311867226.237839.png 1311867226.248711 depth/1311867226.248711.png
1311867226.273639 rgb/1311867226.273639.png 1311867226.282993 depth/1311867226.282993.png
1311867226.305637 rgb/1311867226.305637.png 1311867226.321131 depth/1311867226.321131.png
1311867226.337609 rgb/1311867226.337609.png 1311867226.345582 depth/1311867226.345582.png
1311867226.373734 rgb/1311867226.373734.png 1311867226.387308 depth/1311867226.387308.png
1311867226.405602 rgb/1311867226.405602.png 1311867226.418875 depth/1311867226.418875.png
1311867226.437644 rgb/1311867226.437644.png 1311867226.447274 depth/1311867226.447274.png
1311867226.473717 rgb/1311867226.473717.png 1311867226.484957 depth/1311867226.484957.png
1311867226.505750 rgb/1311867226.505750.png 1311867226.516784 depth/1311867226.516784.png
1311867226.537741 rgb/1311867226.537741.png 1311867226.546219 depth/1311867226.546219.png
1311867226.573767 rgb/1311867226.573767.png 1311867226.584229 depth/1311867226.584229.png
1311867226.605613 rgb/1311867226.605613.png 1311867226.614960 depth/1311867226.614960.png
1311867226.637797 rgb/1311867226.637797.png 1311867226.654529 depth/1311867226.654529.png
1311867226.673676 rgb/1311867226.673676.png 1311867226.680215 depth/1311867226.680215.png
1311867226.705658 rgb/1311867226.705658.png 1311867226.714235 depth/1311867226.714235.png
1311867226.737728 rgb/1311867226.737728.png 1311867226.750659 depth/1311867226.750659.png
1311867226.773860 rgb/1311867226.773860.png 1311867226.781808 depth/1311867226.781808.png
1311867226.805637 rgb/1311867226.805637.png 1311867226.813308 depth/1311867226.813308.png
1311867226.837753 rgb/1311867226.837753.png 1311867226.851361 depth/1311867226.851361.png
1311867226.873821 rgb/1311867226.873821.png 1311867226.883868 depth/1311867226.883868.png
1311867226.905774 rgb/1311867226.905774.png 1311867226.918156 depth/1311867226.918156.png
1311867226.937813 rgb/1311867226.937813.png 1311867226.951490 depth/1311867226.951490.png
1311867226.973631 rgb/1311867226.973631.png 1311867226.981015 depth/1311867226.981015.png
1311867227.005676 rgb/1311867227.005676.png 1311867227.012562 depth/1311867227.012562.png
1311867227.037802 rgb/1311867227.037802.png 1311867227.048067 depth/1311867227.048067.png
1311867227.073659 rgb/1311867227.073659.png 1311867227.086193 depth/1311867227.086193.png
1311867227.105662 rgb/1311867227.105662.png 1311867227.115819 depth/1311867227.115819.png
1311867227.137793 rgb/1311867227.137793.png 1311867227.150400 depth/1311867227.150400.png
1311867227.173840 rgb/1311867227.173840.png 1311867227.184159 depth/1311867227.184159.png
1311867227.205749 rgb/1311867227.205749.png 1311867227.214845 depth/1311867227.214845.png
1311867227.237947 rgb/1311867227.237947.png 1311867227.248026 depth/1311867227.248026.png
1311867227.273709 rgb/1311867227.273709.png 1311867227.281980 depth/1311867227.281980.png
1311867227.305822 rgb/1311867227.305822.png 1311867227.315250 depth/1311867227.315250.png
1311867227.337747 rgb/1311867227.337747.png 1311867227.347984 depth/1311867227.347984.png
1311867227.373776 rgb/1311867227.373776.png 1311867227.384107 depth/1311867227.384107.png
1311867227.405700 rgb/1311867227.405700.png 1311867227.414144 depth/1311867227.414144.png
1311867227.437755 rgb/1311867227.437755.png 1311867227.447920 depth/1311867227.447920.png
1311867227.473739 rgb/1311867227.473739.png 1311867227.481876 depth/1311867227.481876.png
1311867227.505780 rgb/1311867227.505780.png 1311867227.516933 depth/1311867227.516933.png
1311867227.537934 rgb/1311867227.537934.png 1311867227.550122 depth/1311867227.550122.png
1311867227.573742 rgb/1311867227.573742.png 1311867227.581954 depth/1311867227.581954.png
1311867227.605850 rgb/1311867227.605850.png 1311867227.616275 depth/1311867227.616275.png
1311867227.637919 rgb/1311867227.637919.png 1311867227.650308 depth/1311867227.650308.png
1311867227.673930 rgb/1311867227.673930.png 1311867227.682398 depth/1311867227.682398.png
1311867227.705960 rgb/1311867227.705960.png 1311867227.713593 depth/1311867227.713593.png
1311867227.737825 rgb/1311867227.737825.png 1311867227.749637 depth/1311867227.749637.png
1311867227.773732 rgb/1311867227.773732.png 1311867227.782762 depth/1311867227.782762.png
1311867227.805861 rgb/1311867227.805861.png 1311867227.814155 depth/1311867227.814155.png
1311867227.837774 rgb/1311867227.837774.png 1311867227.849769 depth/1311867227.849769.png
1311867227.873834 rgb/1311867227.873834.png 1311867227.883287 depth/1311867227.883287.png
1311867227.905791 rgb/1311867227.905791.png 1311867227.919694 depth/1311867227.919694.png
1311867227.937974 rgb/1311867227.937974.png 1311867227.951678 depth/1311867227.951678.png
1311867227.973753 rgb/1311867227.973753.png 1311867227.982859 depth/1311867227.982859.png
1311867228.005723 rgb/1311867228.005723.png 1311867228.018191 depth/1311867228.018191.png
1311867228.037953 rgb/1311867228.037953.png 1311867228.051633 depth/1311867228.051633.png
1311867228.073892 rgb/1311867228.073892.png 1311867228.082533 depth/1311867228.082533.png
1311867228.105804 rgb/1311867228.105804.png 1311867228.117984 depth/1311867228.117984.png
1311867228.137844 rgb/1311867228.137844.png 1311867228.151139 depth/1311867228.151139.png
1311867228.173814 rgb/1311867228.173814.png 1311867228.182861 depth/1311867228.182861.png
1311867228.205739 rgb/1311867228.205739.png 1311867228.217942 depth/1311867228.217942.png
1311867228.237933 rgb/1311867228.237933.png 1311867228.254125 depth/1311867228.254125.png
1311867228.273761 rgb/1311867228.273761.png 1311867228.282652 depth/1311867228.282652.png
1311867228.305921 rgb/1311867228.305921.png 1311867228.318174 depth/1311867228.318174.png
1311867228.337798 rgb/1311867228.337798.png 1311867228.350452 depth/1311867228.350452.png
1311867228.373868 rgb/1311867228.373868.png 1311867228.382478 depth/1311867228.382478.png
1311867228.405817 rgb/1311867228.405817.png 1311867228.417676 depth/1311867228.417676.png
1311867228.437784 rgb/1311867228.437784.png 1311867228.448304 depth/1311867228.448304.png
1311867228.473891 rgb/1311867228.473891.png 1311867228.483532 depth/1311867228.483532.png
1311867228.505808 rgb/1311867228.505808.png 1311867228.517790 depth/1311867228.517790.png
1311867228.537902 rgb/1311867228.537902.png 1311867228.552964 depth/1311867228.552964.png
1311867228.573967 rgb/1311867228.573967.png 1311867228.583412 depth/1311867228.583412.png
1311867228.605785 rgb/1311867228.605785.png 1311867228.616884 depth/1311867228.616884.png
1311867228.638238 rgb/1311867228.638238.png 1311867228.651354 depth/1311867228.651354.png
1311867228.705963 rgb/1311867228.705963.png 1311867228.696091 depth/1311867228.696091.png
1311867228.738100 rgb/1311867228.738100.png 1311867228.725113 depth/1311867228.725113.png
1311867228.773802 rgb/1311867228.773802.png 1311867228.787273 depth/1311867228.787273.png
1311867228.805984 rgb/1311867228.805984.png 1311867228.818499 depth/1311867228.818499.png
1311867228.838559 rgb/1311867228.838559.png 1311867228.851219 depth/1311867228.851219.png
1311867228.873961 rgb/1311867228.873961.png 1311867228.883505 depth/1311867228.883505.png
1311867228.906015 rgb/1311867228.906015.png 1311867228.918145 depth/1311867228.918145.png
1311867228.937917 rgb/1311867228.937917.png 1311867228.949649 depth/1311867228.949649.png
1311867228.974031 rgb/1311867228.974031.png 1311867228.984476 depth/1311867228.984476.png
1311867229.006218 rgb/1311867229.006218.png 1311867229.023845 depth/1311867229.023845.png
1311867229.037895 rgb/1311867229.037895.png 1311867229.050928 depth/1311867229.050928.png
1311867229.073863 rgb/1311867229.073863.png 1311867229.087432 depth/1311867229.087432.png
1311867229.106048 rgb/1311867229.106048.png 1311867229.121808 depth/1311867229.121808.png
1311867229.138415 rgb/1311867229.138415.png 1311867229.151714 depth/1311867229.151714.png
1311867229.173882 rgb/1311867229.173882.png 1311867229.189054 depth/1311867229.189054.png
1311867229.205881 rgb/1311867229.205881.png 1311867229.221434 depth/1311867229.221434.png
1311867229.237989 rgb/1311867229.237989.png 1311867229.253298 depth/1311867229.253298.png
1311867229.273846 rgb/1311867229.273846.png 1311867229.284135 depth/1311867229.284135.png
1311867229.305876 rgb/1311867229.305876.png 1311867229.319302 depth/1311867229.319302.png
1311867229.338430 rgb/1311867229.338430.png 1311867229.350224 depth/1311867229.350224.png
1311867229.373891 rgb/1311867229.373891.png 1311867229.385071 depth/1311867229.385071.png
1311867229.405824 rgb/1311867229.405824.png 1311867229.418047 depth/1311867229.418047.png
1311867229.438754 rgb/1311867229.438754.png 1311867229.448374 depth/1311867229.448374.png
1311867229.473780 rgb/1311867229.473780.png 1311867229.484336 depth/1311867229.484336.png
1311867229.505914 rgb/1311867229.505914.png 1311867229.518993 depth/1311867229.518993.png
1311867229.538044 rgb/1311867229.538044.png 1311867229.550458 depth/1311867229.550458.png
1311867229.573925 rgb/1311867229.573925.png 1311867229.585338 depth/1311867229.585338.png
1311867229.605773 rgb/1311867229.605773.png 1311867229.618280 depth/1311867229.618280.png
1311867229.637979 rgb/1311867229.637979.png 1311867229.650316 depth/1311867229.650316.png
1311867229.673818 rgb/1311867229.673818.png 1311867229.687698 depth/1311867229.687698.png
1311867229.705799 rgb/1311867229.705799.png 1311867229.718422 depth/1311867229.718422.png
1311867229.737926 rgb/1311867229.737926.png 1311867229.750000 depth/1311867229.750000.png
1311867229.773985 rgb/1311867229.773985.png 1311867229.785433 depth/1311867229.785433.png
1311867229.805829 rgb/1311867229.805829.png 1311867229.818483 depth/1311867229.818483.png
1311867229.837864 rgb/1311867229.837864.png 1311867229.849428 depth/1311867229.849428.png
1311867229.874033 rgb/1311867229.874033.png 1311867229.885334 depth/1311867229.885334.png
1311867229.905852 rgb/1311867229.905852.png 1311867229.918314 depth/1311867229.918314.png
1311867229.938195 rgb/1311867229.938195.png 1311867229.953416 depth/1311867229.953416.png
1311867229.973952 rgb/1311867229.973952.png 1311867229.987775 depth/1311867229.987775.png
1311867230.005885 rgb/1311867230.005885.png 1311867230.019488 depth/1311867230.019488.png
1311867230.037850 rgb/1311867230.037850.png 1311867230.051261 depth/1311867230.051261.png
1311867230.074069 rgb/1311867230.074069.png 1311867230.087604 depth/1311867230.087604.png
1311867230.105927 rgb/1311867230.105927.png 1311867230.121203 depth/1311867230.121203.png
1311867230.138081 rgb/1311867230.138081.png 1311867230.150813 depth/1311867230.150813.png
1311867230.173877 rgb/1311867230.173877.png 1311867230.187230 depth/1311867230.187230.png
1311867230.206050 rgb/1311867230.206050.png 1311867230.219479 depth/1311867230.219479.png
1311867230.238178 rgb/1311867230.238178.png 1311867230.249421 depth/1311867230.249421.png
1311867230.274102 rgb/1311867230.274102.png 1311867230.289479 depth/1311867230.289479.png
1311867230.305950 rgb/1311867230.305950.png 1311867230.318943 depth/1311867230.318943.png
1311867230.337872 rgb/1311867230.337872.png 1311867230.355201 depth/1311867230.355201.png
1311867230.374067 rgb/1311867230.374067.png 1311867230.391314 depth/1311867230.391314.png
1311867230.406184 rgb/1311867230.406184.png 1311867230.416993 depth/1311867230.416993.png
1311867230.437986 rgb/1311867230.437986.png 1311867230.453894 depth/1311867230.453894.png
1311867230.474028 rgb/1311867230.474028.png 1311867230.489211 depth/1311867230.489211.png
1311867230.506080 rgb/1311867230.506080.png 1311867230.521643 depth/1311867230.521643.png
1311867230.574088 rgb/1311867230.574088.png 1311867230.556415 depth/1311867230.556415.png
1311867230.605959 rgb/1311867230.605959.png 1311867230.618415 depth/1311867230.618415.png
1311867230.638052 rgb/1311867230.638052.png 1311867230.653440 depth/1311867230.653440.png
1311867230.674058 rgb/1311867230.674058.png 1311867230.692078 depth/1311867230.692078.png
1311867230.705904 rgb/1311867230.705904.png 1311867230.718519 depth/1311867230.718519.png
1311867230.737957 rgb/1311867230.737957.png 1311867230.752912 depth/1311867230.752912.png
1311867230.774137 rgb/1311867230.774137.png 1311867230.787161 depth/1311867230.787161.png
1311867230.805901 rgb/1311867230.805901.png 1311867230.819574 depth/1311867230.819574.png
1311867230.838169 rgb/1311867230.838169.png 1311867230.853418 depth/1311867230.853418.png
1311867230.874133 rgb/1311867230.874133.png 1311867230.889016 depth/1311867230.889016.png
1311867230.905947 rgb/1311867230.905947.png 1311867230.917651 depth/1311867230.917651.png
1311867230.938299 rgb/1311867230.938299.png 1311867230.955917 depth/1311867230.955917.png
1311867230.973924 rgb/1311867230.973924.png 1311867230.988101 depth/1311867230.988101.png
1311867231.006219 rgb/1311867231.006219.png 1311867231.016628 depth/1311867231.016628.png
1311867231.074099 rgb/1311867231.074099.png 1311867231.086862 depth/1311867231.086862.png
1311867231.105954 rgb/1311867231.105954.png 1311867231.122102 depth/1311867231.122102.png
1311867231.138242 rgb/1311867231.138242.png 1311867231.152380 depth/1311867231.152380.png
1311867231.174250 rgb/1311867231.174250.png 1311867231.186007 depth/1311867231.186007.png
1311867231.205918 rgb/1311867231.205918.png 1311867231.218827 depth/1311867231.218827.png
1311867231.238184 rgb/1311867231.238184.png 1311867231.252262 depth/1311867231.252262.png
1311867231.274090 rgb/1311867231.274090.png 1311867231.286411 depth/1311867231.286411.png
1311867231.306019 rgb/1311867231.306019.png 1311867231.321594 depth/1311867231.321594.png
1311867231.338149 rgb/1311867231.338149.png 1311867231.352551 depth/1311867231.352551.png
1311867231.374183 rgb/1311867231.374183.png 1311867231.387465 depth/1311867231.387465.png
1311867231.405990 rgb/1311867231.405990.png 1311867231.418704 depth/1311867231.418704.png
1311867231.438072 rgb/1311867231.438072.png 1311867231.454240 depth/1311867231.454240.png
1311867231.474140 rgb/1311867231.474140.png 1311867231.486799 depth/1311867231.486799.png
1311867231.505980 rgb/1311867231.505980.png 1311867231.519303 depth/1311867231.519303.png
1311867231.538096 rgb/1311867231.538096.png 1311867231.552415 depth/1311867231.552415.png
1311867231.574153 rgb/1311867231.574153.png 1311867231.585585 depth/1311867231.585585.png
1311867231.605955 rgb/1311867231.605955.png 1311867231.621082 depth/1311867231.621082.png
1311867231.638125 rgb/1311867231.638125.png 1311867231.652217 depth/1311867231.652217.png
1311867231.674142 rgb/1311867231.674142.png 1311867231.688050 depth/1311867231.688050.png
1311867231.705921 rgb/1311867231.705921.png 1311867231.720809 depth/1311867231.720809.png
1311867231.738011 rgb/1311867231.738011.png 1311867231.752308 depth/1311867231.752308.png
1311867231.774173 rgb/1311867231.774173.png 1311867231.786059 depth/1311867231.786059.png
1311867231.805931 rgb/1311867231.805931.png 1311867231.820213 depth/1311867231.820213.png
1311867231.838039 rgb/1311867231.838039.png 1311867231.852184 depth/1311867231.852184.png
1311867231.873920 rgb/1311867231.873920.png 1311867231.885750 depth/1311867231.885750.png
1311867231.905983 rgb/1311867231.905983.png 1311867231.920856 depth/1311867231.920856.png
1311867231.938028 rgb/1311867231.938028.png 1311867231.953318 depth/1311867231.953318.png
1311867231.974086 rgb/1311867231.974086.png 1311867231.987049 depth/1311867231.987049.png
1311867232.006124 rgb/1311867232.006124.png 1311867232.020286 depth/1311867232.020286.png
1311867232.038052 rgb/1311867232.038052.png 1311867232.052242 depth/1311867232.052242.png
1311867232.074075 rgb/1311867232.074075.png 1311867232.087849 depth/1311867232.087849.png
1311867232.106162 rgb/1311867232.106162.png 1311867232.120324 depth/1311867232.120324.png
1311867232.138161 rgb/1311867232.138161.png 1311867232.154551 depth/1311867232.154551.png
1311867232.173947 rgb/1311867232.173947.png 1311867232.184618 depth/1311867232.184618.png
1311867232.206061 rgb/1311867232.206061.png 1311867232.220978 depth/1311867232.220978.png
1311867232.241970 rgb/1311867232.241970.png 1311867232.253112 depth/1311867232.253112.png
1311867232.273986 rgb/1311867232.273986.png 1311867232.284448 depth/1311867232.284448.png
1311867232.305979 rgb/1311867232.305979.png 1311867232.320979 depth/1311867232.320979.png
1311867232.342085 rgb/1311867232.342085.png 1311867232.354466 depth/1311867232.354466.png
1311867232.374074 rgb/1311867232.374074.png 1311867232.385891 depth/1311867232.385891.png
1311867232.405964 rgb/1311867232.405964.png 1311867232.420391 depth/1311867232.420391.png
1311867232.442125 rgb/1311867232.442125.png 1311867232.454456 depth/1311867232.454456.png
1311867232.473958 rgb/1311867232.473958.png 1311867232.484601 depth/1311867232.484601.png
1311867232.505952 rgb/1311867232.505952.png 1311867232.520303 depth/1311867232.520303.png
1311867232.542122 rgb/1311867232.542122.png 1311867232.555005 depth/1311867232.555005.png
1311867232.573937 rgb/1311867232.573937.png 1311867232.584432 depth/1311867232.584432.png
1311867232.606133 rgb/1311867232.606133.png 1311867232.620160 depth/1311867232.620160.png
1311867232.642128 rgb/1311867232.642128.png 1311867232.655486 depth/1311867232.655486.png
1311867232.674004 rgb/1311867232.674004.png 1311867232.685049 depth/1311867232.685049.png
1311867232.706009 rgb/1311867232.706009.png 1311867232.721032 depth/1311867232.721032.png
1311867232.742111 rgb/1311867232.742111.png 1311867232.753952 depth/1311867232.753952.png
1311867232.774049 rgb/1311867232.774049.png 1311867232.788581 depth/1311867232.788581.png
1311867232.805985 rgb/1311867232.805985.png 1311867232.820617 depth/1311867232.820617.png
1311867232.842129 rgb/1311867232.842129.png 1311867232.853937 depth/1311867232.853937.png
1311867232.874052 rgb/1311867232.874052.png 1311867232.888271 depth/1311867232.888271.png
1311867232.906135 rgb/1311867232.906135.png 1311867232.920377 depth/1311867232.920377.png
1311867232.942097 rgb/1311867232.942097.png 1311867232.955990 depth/1311867232.955990.png
1311867232.974275 rgb/1311867232.974275.png 1311867232.989004 depth/1311867232.989004.png
1311867233.006058 rgb/1311867233.006058.png 1311867233.021226 depth/1311867233.021226.png
1311867233.042232 rgb/1311867233.042232.png 1311867233.056929 depth/1311867233.056929.png
1311867233.108859 rgb/1311867233.108859.png 1311867233.094320 depth/1311867233.094320.png
1311867233.142135 rgb/1311867233.142135.png 1311867233.153080 depth/1311867233.153080.png
1311867233.174057 rgb/1311867233.174057.png 1311867233.188768 depth/1311867233.188768.png
1311867233.206774 rgb/1311867233.206774.png 1311867233.221048 depth/1311867233.221048.png
1311867233.274216 rgb/1311867233.274216.png 1311867233.259018 depth/1311867233.259018.png
1311867233.306062 rgb/1311867233.306062.png 1311867233.321221 depth/1311867233.321221.png
1311867233.342453 rgb/1311867233.342453.png 1311867233.353385 depth/1311867233.353385.png
1311867233.374066 rgb/1311867233.374066.png 1311867233.388456 depth/1311867233.388456.png
1311867233.406026 rgb/1311867233.406026.png 1311867233.423667 depth/1311867233.423667.png
1311867233.442194 rgb/1311867233.442194.png 1311867233.452270 depth/1311867233.452270.png
1311867233.474076 rgb/1311867233.474076.png 1311867233.488161 depth/1311867233.488161.png
1311867233.506601 rgb/1311867233.506601.png 1311867233.520120 depth/1311867233.520120.png
1311867233.542082 rgb/1311867233.542082.png 1311867233.552627 depth/1311867233.552627.png
1311867233.574217 rgb/1311867233.574217.png 1311867233.589085 depth/1311867233.589085.png
1311867233.606173 rgb/1311867233.606173.png 1311867233.620262 depth/1311867233.620262.png
1311867233.642267 rgb/1311867233.642267.png 1311867233.653908 depth/1311867233.653908.png
1311867233.674202 rgb/1311867233.674202.png 1311867233.687929 depth/1311867233.687929.png
1311867233.706461 rgb/1311867233.706461.png 1311867233.719779 depth/1311867233.719779.png
1311867233.742420 rgb/1311867233.742420.png 1311867233.757754 depth/1311867233.757754.png
1311867233.774073 rgb/1311867233.774073.png 1311867233.789609 depth/1311867233.789609.png
1311867233.806227 rgb/1311867233.806227.png 1311867233.822119 depth/1311867233.822119.png
1311867233.842183 rgb/1311867233.842183.png 1311867233.856245 depth/1311867233.856245.png
1311867233.874229 rgb/1311867233.874229.png 1311867233.888569 depth/1311867233.888569.png
1311867233.906084 rgb/1311867233.906084.png 1311867233.920345 depth/1311867233.920345.png
1311867233.942192 rgb/1311867233.942192.png 1311867233.955291 depth/1311867233.955291.png
1311867233.974249 rgb/1311867233.974249.png 1311867233.988590 depth/1311867233.988590.png
1311867234.006205 rgb/1311867234.006205.png 1311867234.020583 depth/1311867234.020583.png
1311867234.042205 rgb/1311867234.042205.png 1311867234.056624 depth/1311867234.056624.png
1311867234.074349 rgb/1311867234.074349.png 1311867234.090717 depth/1311867234.090717.png
1311867234.106175 rgb/1311867234.106175.png 1311867234.121452 depth/1311867234.121452.png
1311867234.142473 rgb/1311867234.142473.png 1311867234.156169 depth/1311867234.156169.png
1311867234.174383 rgb/1311867234.174383.png 1311867234.189256 depth/1311867234.189256.png
1311867234.206312 rgb/1311867234.206312.png 1311867234.220360 depth/1311867234.220360.png
1311867234.242292 rgb/1311867234.242292.png 1311867234.258893 depth/1311867234.258893.png
1311867234.274294 rgb/1311867234.274294.png 1311867234.289532 depth/1311867234.289532.png
1311867234.306469 rgb/1311867234.306469.png 1311867234.321320 depth/1311867234.321320.png
1311867234.342355 rgb/1311867234.342355.png 1311867234.357013 depth/1311867234.357013.png
1311867234.374159 rgb/1311867234.374159.png 1311867234.388577 depth/1311867234.388577.png
1311867234.406260 rgb/1311867234.406260.png 1311867234.420491 depth/1311867234.420491.png
1311867234.442238 rgb/1311867234.442238.png 1311867234.457992 depth/1311867234.457992.png
1311867234.474248 rgb/1311867234.474248.png 1311867234.487896 depth/1311867234.487896.png
1311867234.506308 rgb/1311867234.506308.png 1311867234.520124 depth/1311867234.520124.png
1311867234.542293 rgb/1311867234.542293.png 1311867234.559428 depth/1311867234.559428.png
1311867234.574192 rgb/1311867234.574192.png 1311867234.588238 depth/1311867234.588238.png
1311867234.606098 rgb/1311867234.606098.png 1311867234.620420 depth/1311867234.620420.png
1311867234.642267 rgb/1311867234.642267.png 1311867234.659091 depth/1311867234.659091.png
1311867234.674096 rgb/1311867234.674096.png 1311867234.688046 depth/1311867234.688046.png
1311867234.706095 rgb/1311867234.706095.png 1311867234.719878 depth/1311867234.719878.png
1311867234.742287 rgb/1311867234.742287.png 1311867234.758618 depth/1311867234.758618.png
1311867234.774140 rgb/1311867234.774140.png 1311867234.788261 depth/1311867234.788261.png
1311867234.806072 rgb/1311867234.806072.png 1311867234.820656 depth/1311867234.820656.png
1311867234.842326 rgb/1311867234.842326.png 1311867234.859025 depth/1311867234.859025.png
1311867234.874157 rgb/1311867234.874157.png 1311867234.888123 depth/1311867234.888123.png
1311867234.906187 rgb/1311867234.906187.png 1311867234.920493 depth/1311867234.920493.png
1311867234.942270 rgb/1311867234.942270.png 1311867234.956609 depth/1311867234.956609.png
1311867234.974155 rgb/1311867234.974155.png 1311867234.990409 depth/1311867234.990409.png
1311867235.006175 rgb/1311867235.006175.png 1311867235.020599 depth/1311867235.020599.png
1311867235.042326 rgb/1311867235.042326.png 1311867235.056381 depth/1311867235.056381.png
1311867235.074182 rgb/1311867235.074182.png 1311867235.091115 depth/1311867235.091115.png
1311867235.106252 rgb/1311867235.106252.png 1311867235.120814 depth/1311867235.120814.png
1311867235.142245 rgb/1311867235.142245.png 1311867235.156407 depth/1311867235.156407.png
1311867235.174301 rgb/1311867235.174301.png 1311867235.188568 depth/1311867235.188568.png
1311867235.206197 rgb/1311867235.206197.png 1311867235.220209 depth/1311867235.220209.png
1311867235.242257 rgb/1311867235.242257.png 1311867235.257626 depth/1311867235.257626.png
1311867235.274183 rgb/1311867235.274183.png 1311867235.289966 depth/1311867235.289966.png
1311867235.306202 rgb/1311867235.306202.png 1311867235.324783 depth/1311867235.324783.png
1311867235.342289 rgb/1311867235.342289.png 1311867235.356780 depth/1311867235.356780.png
1311867235.374391 rgb/1311867235.374391.png 1311867235.388628 depth/1311867235.388628.png
1311867235.406214 rgb/1311867235.406214.png 1311867235.424619 depth/1311867235.424619.png
1311867235.442222 rgb/1311867235.442222.png 1311867235.456485 depth/1311867235.456485.png
1311867235.474167 rgb/1311867235.474167.png 1311867235.489793 depth/1311867235.489793.png
1311867235.506159 rgb/1311867235.506159.png 1311867235.524072 depth/1311867235.524072.png
1311867235.542321 rgb/1311867235.542321.png 1311867235.557729 depth/1311867235.557729.png
1311867235.574193 rgb/1311867235.574193.png 1311867235.588064 depth/1311867235.588064.png
1311867235.606195 rgb/1311867235.606195.png 1311867235.624994 depth/1311867235.624994.png
1311867235.642444 rgb/1311867235.642444.png 1311867235.656327 depth/1311867235.656327.png
1311867235.674238 rgb/1311867235.674238.png 1311867235.688562 depth/1311867235.688562.png
1311867235.706367 rgb/1311867235.706367.png 1311867235.724195 depth/1311867235.724195.png
1311867235.742311 rgb/1311867235.742311.png 1311867235.756172 depth/1311867235.756172.png
1311867235.806313 rgb/1311867235.806313.png 1311867235.790328 depth/1311867235.790328.png
1311867235.842280 rgb/1311867235.842280.png 1311867235.856217 depth/1311867235.856217.png
1311867235.874209 rgb/1311867235.874209.png 1311867235.888105 depth/1311867235.888105.png
1311867235.906374 rgb/1311867235.906374.png 1311867235.923990 depth/1311867235.923990.png
1311867235.942343 rgb/1311867235.942343.png 1311867235.956376 depth/1311867235.956376.png
1311867235.974196 rgb/1311867235.974196.png 1311867235.989095 depth/1311867235.989095.png
1311867236.042378 rgb/1311867236.042378.png 1311867236.025045 depth/1311867236.025045.png
1311867236.074226 rgb/1311867236.074226.png 1311867236.088486 depth/1311867236.088486.png
1311867236.106358 rgb/1311867236.106358.png 1311867236.124704 depth/1311867236.124704.png
1311867236.142358 rgb/1311867236.142358.png 1311867236.158129 depth/1311867236.158129.png
1311867236.174242 rgb/1311867236.174242.png 1311867236.190153 depth/1311867236.190153.png
1311867236.206222 rgb/1311867236.206222.png 1311867236.224233 depth/1311867236.224233.png
1311867236.274266 rgb/1311867236.274266.png 1311867236.259949 depth/1311867236.259949.png
1311867236.306429 rgb/1311867236.306429.png 1311867236.289042 depth/1311867236.289042.png
1311867236.342291 rgb/1311867236.342291.png 1311867236.356881 depth/1311867236.356881.png
1311867236.374298 rgb/1311867236.374298.png 1311867236.389742 depth/1311867236.389742.png
1311867236.406251 rgb/1311867236.406251.png 1311867236.424339 depth/1311867236.424339.png
1311867236.442391 rgb/1311867236.442391.png 1311867236.456604 depth/1311867236.456604.png
1311867236.506314 rgb/1311867236.506314.png 1311867236.493613 depth/1311867236.493613.png
1311867236.542354 rgb/1311867236.542354.png 1311867236.524700 depth/1311867236.524700.png
1311867236.574217 rgb/1311867236.574217.png 1311867236.560210 depth/1311867236.560210.png
1311867236.606288 rgb/1311867236.606288.png 1311867236.597291 depth/1311867236.597291.png
1311867236.642388 rgb/1311867236.642388.png 1311867236.624658 depth/1311867236.624658.png
1311867236.674478 rgb/1311867236.674478.png 1311867236.660048 depth/1311867236.660048.png
1311867236.706587 rgb/1311867236.706587.png 1311867236.695666 depth/1311867236.695666.png
1311867236.742471 rgb/1311867236.742471.png 1311867236.727637 depth/1311867236.727637.png
1311867236.774407 rgb/1311867236.774407.png 1311867236.761927 depth/1311867236.761927.png
1311867236.806389 rgb/1311867236.806389.png 1311867236.792347 depth/1311867236.792347.png
1311867236.842397 rgb/1311867236.842397.png 1311867236.858344 depth/1311867236.858344.png
1311867236.906286 rgb/1311867236.906286.png 1311867236.892848 depth/1311867236.892848.png
1311867236.942486 rgb/1311867236.942486.png 1311867236.958196 depth/1311867236.958196.png
1311867237.006457 rgb/1311867237.006457.png 1311867236.993729 depth/1311867236.993729.png
1311867237.042352 rgb/1311867237.042352.png 1311867237.024420 depth/1311867237.024420.png
1311867237.074287 rgb/1311867237.074287.png 1311867237.060306 depth/1311867237.060306.png
1311867237.106376 rgb/1311867237.106376.png 1311867237.092759 depth/1311867237.092759.png
1311867237.142401 rgb/1311867237.142401.png 1311867237.156658 depth/1311867237.156658.png
1311867237.206351 rgb/1311867237.206351.png 1311867237.192595 depth/1311867237.192595.png
1311867237.242389 rgb/1311867237.242389.png 1311867237.256958 depth/1311867237.256958.png
1311867237.306833 rgb/1311867237.306833.png 1311867237.294428 depth/1311867237.294428.png
1311867237.342478 rgb/1311867237.342478.png 1311867237.356531 depth/1311867237.356531.png
1311867237.406529 rgb/1311867237.406529.png 1311867237.393498 depth/1311867237.393498.png
1311867237.442502 rgb/1311867237.442502.png 1311867237.457951 depth/1311867237.457951.png
1311867237.506364 rgb/1311867237.506364.png 1311867237.493356 depth/1311867237.493356.png
1311867237.542505 rgb/1311867237.542505.png 1311867237.558123 depth/1311867237.558123.png
1311867237.606410 rgb/1311867237.606410.png 1311867237.592535 depth/1311867237.592535.png
1311867237.642379 rgb/1311867237.642379.png 1311867237.656929 depth/1311867237.656929.png
1311867237.706366 rgb/1311867237.706366.png 1311867237.692501 depth/1311867237.692501.png
1311867237.742584 rgb/1311867237.742584.png 1311867237.724361 depth/1311867237.724361.png
1311867237.774590 rgb/1311867237.774590.png 1311867237.761794 depth/1311867237.761794.png
1311867237.806458 rgb/1311867237.806458.png 1311867237.792681 depth/1311867237.792681.png
1311867237.842501 rgb/1311867237.842501.png 1311867237.825582 depth/1311867237.825582.png
1311867237.874551 rgb/1311867237.874551.png 1311867237.861270 depth/1311867237.861270.png
1311867237.906433 rgb/1311867237.906433.png 1311867237.892606 depth/1311867237.892606.png
1311867237.942660 rgb/1311867237.942660.png 1311867237.925359 depth/1311867237.925359.png
1311867237.974431 rgb/1311867237.974431.png 1311867237.961351 depth/1311867237.961351.png
1311867238.006500 rgb/1311867238.006500.png 1311867237.992891 depth/1311867237.992891.png
1311867238.042572 rgb/1311867238.042572.png 1311867238.024592 depth/1311867238.024592.png
1311867238.074515 rgb/1311867238.074515.png 1311867238.060795 depth/1311867238.060795.png
1311867238.106429 rgb/1311867238.106429.png 1311867238.093263 depth/1311867238.093263.png
1311867238.142402 rgb/1311867238.142402.png 1311867238.125193 depth/1311867238.125193.png
1311867238.174577 rgb/1311867238.174577.png 1311867238.160847 depth/1311867238.160847.png
1311867238.206467 rgb/1311867238.206467.png 1311867238.192851 depth/1311867238.192851.png
1311867238.242454 rgb/1311867238.242454.png 1311867238.224677 depth/1311867238.224677.png
1311867238.274552 rgb/1311867238.274552.png 1311867238.260594 depth/1311867238.260594.png
1311867238.306377 rgb/1311867238.306377.png 1311867238.292679 depth/1311867238.292679.png
1311867238.342532 rgb/1311867238.342532.png 1311867238.325781 depth/1311867238.325781.png
1311867238.374439 rgb/1311867238.374439.png 1311867238.360439 depth/1311867238.360439.png
1311867238.406474 rgb/1311867238.406474.png 1311867238.393638 depth/1311867238.393638.png
1311867238.442421 rgb/1311867238.442421.png 1311867238.426405 depth/1311867238.426405.png
1311867238.474426 rgb/1311867238.474426.png 1311867238.461621 depth/1311867238.461621.png
1311867238.506473 rgb/1311867238.506473.png 1311867238.493255 depth/1311867238.493255.png
1311867238.542703 rgb/1311867238.542703.png 1311867238.524866 depth/1311867238.524866.png
1311867238.574615 rgb/1311867238.574615.png 1311867238.560593 depth/1311867238.560593.png
1311867238.606413 rgb/1311867238.606413.png 1311867238.592912 depth/1311867238.592912.png
1311867238.642378 rgb/1311867238.642378.png 1311867238.624987 depth/1311867238.624987.png
1311867238.674405 rgb/1311867238.674405.png 1311867238.660848 depth/1311867238.660848.png
1311867238.706486 rgb/1311867238.706486.png 1311867238.692936 depth/1311867238.692936.png
1311867238.742522 rgb/1311867238.742522.png 1311867238.724636 depth/1311867238.724636.png
1311867238.774397 rgb/1311867238.774397.png 1311867238.762797 depth/1311867238.762797.png
1311867238.806422 rgb/1311867238.806422.png 1311867238.794992 depth/1311867238.794992.png
1311867238.842541 rgb/1311867238.842541.png 1311867238.824682 depth/1311867238.824682.png
1311867238.874418 rgb/1311867238.874418.png 1311867238.863058 depth/1311867238.863058.png
1311867238.906451 rgb/1311867238.906451.png 1311867238.893389 depth/1311867238.893389.png
1311867238.942510 rgb/1311867238.942510.png 1311867238.927898 depth/1311867238.927898.png
1311867238.974527 rgb/1311867238.974527.png 1311867238.962805 depth/1311867238.962805.png
1311867239.006405 rgb/1311867239.006405.png 1311867238.993782 depth/1311867238.993782.png
1311867239.042587 rgb/1311867239.042587.png 1311867239.028730 depth/1311867239.028730.png
1311867239.074592 rgb/1311867239.074592.png 1311867239.061998 depth/1311867239.061998.png
1311867239.106416 rgb/1311867239.106416.png 1311867239.093924 depth/1311867239.093924.png
1311867239.143039 rgb/1311867239.143039.png 1311867239.135811 depth/1311867239.135811.png
1311867239.174559 rgb/1311867239.174559.png 1311867239.162055 depth/1311867239.162055.png
1311867239.206507 rgb/1311867239.206507.png 1311867239.193657 depth/1311867239.193657.png
1311867239.242615 rgb/1311867239.242615.png 1311867239.229495 depth/1311867239.229495.png
1311867239.274466 rgb/1311867239.274466.png 1311867239.260915 depth/1311867239.260915.png
1311867239.306409 rgb/1311867239.306409.png 1311867239.292879 depth/1311867239.292879.png
1311867239.342486 rgb/1311867239.342486.png 1311867239.329529 depth/1311867239.329529.png
1311867239.374562 rgb/1311867239.374562.png 1311867239.361500 depth/1311867239.361500.png
1311867239.406592 rgb/1311867239.406592.png 1311867239.392841 depth/1311867239.392841.png
1311867239.442634 rgb/1311867239.442634.png 1311867239.429329 depth/1311867239.429329.png
1311867239.474517 rgb/1311867239.474517.png 1311867239.461906 depth/1311867239.461906.png
1311867239.506556 rgb/1311867239.506556.png 1311867239.493825 depth/1311867239.493825.png
1311867239.542637 rgb/1311867239.542637.png 1311867239.529502 depth/1311867239.529502.png
1311867239.574603 rgb/1311867239.574603.png 1311867239.561707 depth/1311867239.561707.png
1311867239.606412 rgb/1311867239.606412.png 1311867239.594491 depth/1311867239.594491.png
1311867239.642581 rgb/1311867239.642581.png 1311867239.628443 depth/1311867239.628443.png
1311867239.674585 rgb/1311867239.674585.png 1311867239.662309 depth/1311867239.662309.png
1311867239.706420 rgb/1311867239.706420.png 1311867239.693124 depth/1311867239.693124.png
1311867239.742532 rgb/1311867239.742532.png 1311867239.728495 depth/1311867239.728495.png
1311867239.774489 rgb/1311867239.774489.png 1311867239.761461 depth/1311867239.761461.png
1311867239.806512 rgb/1311867239.806512.png 1311867239.792615 depth/1311867239.792615.png
1311867239.842582 rgb/1311867239.842582.png 1311867239.830832 depth/1311867239.830832.png
1311867239.874576 rgb/1311867239.874576.png 1311867239.860844 depth/1311867239.860844.png
1311867239.906569 rgb/1311867239.906569.png 1311867239.892907 depth/1311867239.892907.png
1311867239.942408 rgb/1311867239.942408.png 1311867239.930660 depth/1311867239.930660.png
1311867239.976213 rgb/1311867239.976213.png 1311867239.961370 depth/1311867239.961370.png
1311867240.006746 rgb/1311867240.006746.png 1311867239.994822 depth/1311867239.994822.png
1311867240.042506 rgb/1311867240.042506.png 1311867240.029229 depth/1311867240.029229.png
1311867240.074598 rgb/1311867240.074598.png 1311867240.061881 depth/1311867240.061881.png
1311867240.106559 rgb/1311867240.106559.png 1311867240.094551 depth/1311867240.094551.png
1311867240.142844 rgb/1311867240.142844.png 1311867240.129751 depth/1311867240.129751.png
1311867240.174466 rgb/1311867240.174466.png 1311867240.161724 depth/1311867240.161724.png
1311867240.206552 rgb/1311867240.206552.png 1311867240.196313 depth/1311867240.196313.png
1311867240.242433 rgb/1311867240.242433.png 1311867240.229103 depth/1311867240.229103.png
1311867240.274677 rgb/1311867240.274677.png 1311867240.261276 depth/1311867240.261276.png
1311867240.306544 rgb/1311867240.306544.png 1311867240.298125 depth/1311867240.298125.png
1311867240.342481 rgb/1311867240.342481.png 1311867240.328916 depth/1311867240.328916.png
1311867240.374466 rgb/1311867240.374466.png 1311867240.360940 depth/1311867240.360940.png
1311867240.406662 rgb/1311867240.406662.png 1311867240.396789 depth/1311867240.396789.png
1311867240.442598 rgb/1311867240.442598.png 1311867240.428689 depth/1311867240.428689.png
1311867240.474536 rgb/1311867240.474536.png 1311867240.465085 depth/1311867240.465085.png
1311867240.506469 rgb/1311867240.506469.png 1311867240.497290 depth/1311867240.497290.png
1311867240.542590 rgb/1311867240.542590.png 1311867240.530998 depth/1311867240.530998.png
1311867240.574511 rgb/1311867240.574511.png 1311867240.560821 depth/1311867240.560821.png
1311867240.606557 rgb/1311867240.606557.png 1311867240.596599 depth/1311867240.596599.png
1311867240.642795 rgb/1311867240.642795.png 1311867240.629079 depth/1311867240.629079.png
1311867240.674613 rgb/1311867240.674613.png 1311867240.662256 depth/1311867240.662256.png
1311867240.706562 rgb/1311867240.706562.png 1311867240.696880 depth/1311867240.696880.png
1311867240.742631 rgb/1311867240.742631.png 1311867240.729198 depth/1311867240.729198.png
1311867240.774678 rgb/1311867240.774678.png 1311867240.762563 depth/1311867240.762563.png
1311867240.806605 rgb/1311867240.806605.png 1311867240.796572 depth/1311867240.796572.png
1311867240.842940 rgb/1311867240.842940.png 1311867240.829331 depth/1311867240.829331.png
1311867240.874843 rgb/1311867240.874843.png 1311867240.862110 depth/1311867240.862110.png
1311867240.906548 rgb/1311867240.906548.png 1311867240.897350 depth/1311867240.897350.png
1311867240.942559 rgb/1311867240.942559.png 1311867240.929027 depth/1311867240.929027.png
1311867240.974622 rgb/1311867240.974622.png 1311867240.961437 depth/1311867240.961437.png
1311867241.006716 rgb/1311867241.006716.png 1311867240.996845 depth/1311867240.996845.png
1311867241.042623 rgb/1311867241.042623.png 1311867241.031562 depth/1311867241.031562.png
1311867241.074792 rgb/1311867241.074792.png 1311867241.063367 depth/1311867241.063367.png
1311867241.106779 rgb/1311867241.106779.png 1311867241.099010 depth/1311867241.099010.png
1311867241.142854 rgb/1311867241.142854.png 1311867241.128529 depth/1311867241.128529.png
1311867241.174730 rgb/1311867241.174730.png 1311867241.164150 depth/1311867241.164150.png
1311867241.206721 rgb/1311867241.206721.png 1311867241.198012 depth/1311867241.198012.png
1311867241.242631 rgb/1311867241.242631.png 1311867241.231333 depth/1311867241.231333.png
1311867241.275069 rgb/1311867241.275069.png 1311867241.264070 depth/1311867241.264070.png
1311867241.310769 rgb/1311867241.310769.png 1311867241.300061 depth/1311867241.300061.png
1311867241.342582 rgb/1311867241.342582.png 1311867241.329485 depth/1311867241.329485.png
1311867241.374677 rgb/1311867241.374677.png 1311867241.361255 depth/1311867241.361255.png
1311867241.410635 rgb/1311867241.410635.png 1311867241.398114 depth/1311867241.398114.png
1311867241.442620 rgb/1311867241.442620.png 1311867241.430059 depth/1311867241.430059.png
1311867241.474896 rgb/1311867241.474896.png 1311867241.465201 depth/1311867241.465201.png
1311867241.510751 rgb/1311867241.510751.png 1311867241.496979 depth/1311867241.496979.png
1311867241.542602 rgb/1311867241.542602.png 1311867241.533172 depth/1311867241.533172.png
1311867241.574823 rgb/1311867241.574823.png 1311867241.565696 depth/1311867241.565696.png
1311867241.610604 rgb/1311867241.610604.png 1311867241.600248 depth/1311867241.600248.png
1311867241.642627 rgb/1311867241.642627.png 1311867241.629120 depth/1311867241.629120.png
1311867241.674668 rgb/1311867241.674668.png 1311867241.664679 depth/1311867241.664679.png
1311867241.710757 rgb/1311867241.710757.png 1311867241.699926 depth/1311867241.699926.png
1311867241.742749 rgb/1311867241.742749.png 1311867241.729765 depth/1311867241.729765.png
1311867241.774620 rgb/1311867241.774620.png 1311867241.767664 depth/1311867241.767664.png
1311867241.810714 rgb/1311867241.810714.png 1311867241.797485 depth/1311867241.797485.png
1311867241.842840 rgb/1311867241.842840.png 1311867241.829655 depth/1311867241.829655.png
1311867241.874966 rgb/1311867241.874966.png 1311867241.866892 depth/1311867241.866892.png
1311867241.910597 rgb/1311867241.910597.png 1311867241.897969 depth/1311867241.897969.png
1311867241.942934 rgb/1311867241.942934.png 1311867241.929262 depth/1311867241.929262.png
1311867241.974655 rgb/1311867241.974655.png 1311867241.965404 depth/1311867241.965404.png
1311867242.010806 rgb/1311867242.010806.png 1311867241.997403 depth/1311867241.997403.png
1311867242.042670 rgb/1311867242.042670.png 1311867242.029634 depth/1311867242.029634.png
1311867242.074787 rgb/1311867242.074787.png 1311867242.067006 depth/1311867242.067006.png
1311867242.110732 rgb/1311867242.110732.png 1311867242.097251 depth/1311867242.097251.png
1311867242.142880 rgb/1311867242.142880.png 1311867242.130804 depth/1311867242.130804.png
1311867242.174884 rgb/1311867242.174884.png 1311867242.167018 depth/1311867242.167018.png
1311867242.210643 rgb/1311867242.210643.png 1311867242.198241 depth/1311867242.198241.png
1311867242.242719 rgb/1311867242.242719.png 1311867242.233437 depth/1311867242.233437.png
1311867242.275028 rgb/1311867242.275028.png 1311867242.269660 depth/1311867242.269660.png
1311867242.310756 rgb/1311867242.310756.png 1311867242.298243 depth/1311867242.298243.png
1311867242.342625 rgb/1311867242.342625.png 1311867242.329349 depth/1311867242.329349.png
1311867242.374628 rgb/1311867242.374628.png 1311867242.365946 depth/1311867242.365946.png
1311867242.410601 rgb/1311867242.410601.png 1311867242.397480 depth/1311867242.397480.png
1311867242.442670 rgb/1311867242.442670.png 1311867242.432277 depth/1311867242.432277.png
1311867242.474794 rgb/1311867242.474794.png 1311867242.464899 depth/1311867242.464899.png
1311867242.510745 rgb/1311867242.510745.png 1311867242.497561 depth/1311867242.497561.png
1311867242.542677 rgb/1311867242.542677.png 1311867242.529257 depth/1311867242.529257.png
1311867242.574755 rgb/1311867242.574755.png 1311867242.565094 depth/1311867242.565094.png
1311867242.610840 rgb/1311867242.610840.png 1311867242.598503 depth/1311867242.598503.png
1311867242.642862 rgb/1311867242.642862.png 1311867242.630559 depth/1311867242.630559.png
1311867242.674755 rgb/1311867242.674755.png 1311867242.669274 depth/1311867242.669274.png
1311867242.710770 rgb/1311867242.710770.png 1311867242.698104 depth/1311867242.698104.png
1311867242.742836 rgb/1311867242.742836.png 1311867242.737283 depth/1311867242.737283.png
1311867242.774742 rgb/1311867242.774742.png 1311867242.765690 depth/1311867242.765690.png
1311867242.810922 rgb/1311867242.810922.png 1311867242.799409 depth/1311867242.799409.png
1311867242.842725 rgb/1311867242.842725.png 1311867242.835554 depth/1311867242.835554.png
1311867242.874716 rgb/1311867242.874716.png 1311867242.866672 depth/1311867242.866672.png
1311867242.910777 rgb/1311867242.910777.png 1311867242.898093 depth/1311867242.898093.png
1311867242.942636 rgb/1311867242.942636.png 1311867242.933550 depth/1311867242.933550.png
1311867242.974656 rgb/1311867242.974656.png 1311867242.965000 depth/1311867242.965000.png
1311867243.010665 rgb/1311867243.010665.png 1311867242.997082 depth/1311867242.997082.png
1311867243.042682 rgb/1311867243.042682.png 1311867243.033253 depth/1311867243.033253.png
1311867243.074944 rgb/1311867243.074944.png 1311867243.064869 depth/1311867243.064869.png
1311867243.110760 rgb/1311867243.110760.png 1311867243.097216 depth/1311867243.097216.png
1311867243.142942 rgb/1311867243.142942.png 1311867243.135710 depth/1311867243.135710.png
1311867243.174792 rgb/1311867243.174792.png 1311867243.165596 depth/1311867243.165596.png
1311867243.210671 rgb/1311867243.210671.png 1311867243.197717 depth/1311867243.197717.png
1311867243.242923 rgb/1311867243.242923.png 1311867243.235886 depth/1311867243.235886.png
1311867243.274872 rgb/1311867243.274872.png 1311867243.264924 depth/1311867243.264924.png
1311867243.310909 rgb/1311867243.310909.png 1311867243.297022 depth/1311867243.297022.png
1311867243.342681 rgb/1311867243.342681.png 1311867243.332754 depth/1311867243.332754.png
1311867243.375787 rgb/1311867243.375787.png 1311867243.368156 depth/1311867243.368156.png
1311867243.412082 rgb/1311867243.412082.png 1311867243.402182 depth/1311867243.402182.png
1311867243.442886 rgb/1311867243.442886.png 1311867243.434433 depth/1311867243.434433.png
1311867243.474884 rgb/1311867243.474884.png 1311867243.466551 depth/1311867243.466551.png
1311867243.510986 rgb/1311867243.510986.png 1311867243.498214 depth/1311867243.498214.png
1311867243.543026 rgb/1311867243.543026.png 1311867243.533978 depth/1311867243.533978.png
1311867243.574697 rgb/1311867243.574697.png 1311867243.566972 depth/1311867243.566972.png
1311867243.610776 rgb/1311867243.610776.png 1311867243.597834 depth/1311867243.597834.png
1311867243.642685 rgb/1311867243.642685.png 1311867243.633372 depth/1311867243.633372.png
1311867243.674867 rgb/1311867243.674867.png 1311867243.666153 depth/1311867243.666153.png
1311867243.710902 rgb/1311867243.710902.png 1311867243.698185 depth/1311867243.698185.png
1311867243.742761 rgb/1311867243.742761.png 1311867243.734471 depth/1311867243.734471.png
1311867243.774837 rgb/1311867243.774837.png 1311867243.766630 depth/1311867243.766630.png
1311867243.810755 rgb/1311867243.810755.png 1311867243.797977 depth/1311867243.797977.png
1311867243.842825 rgb/1311867243.842825.png 1311867243.833024 depth/1311867243.833024.png
1311867243.874795 rgb/1311867243.874795.png 1311867243.864769 depth/1311867243.864769.png
1311867243.911010 rgb/1311867243.911010.png 1311867243.896874 depth/1311867243.896874.png
1311867243.942765 rgb/1311867243.942765.png 1311867243.932996 depth/1311867243.932996.png
1311867243.974939 rgb/1311867243.974939.png 1311867243.966059 depth/1311867243.966059.png
1311867244.010938 rgb/1311867244.010938.png 1311867244.001674 depth/1311867244.001674.png
1311867244.042874 rgb/1311867244.042874.png 1311867244.034138 depth/1311867244.034138.png
1311867244.074729 rgb/1311867244.074729.png 1311867244.065579 depth/1311867244.065579.png
1311867244.110737 rgb/1311867244.110737.png 1311867244.101093 depth/1311867244.101093.png
1311867244.142752 rgb/1311867244.142752.png 1311867244.135309 depth/1311867244.135309.png
1311867244.174960 rgb/1311867244.174960.png 1311867244.164842 depth/1311867244.164842.png
1311867244.210998 rgb/1311867244.210998.png 1311867244.202474 depth/1311867244.202474.png
1311867244.242837 rgb/1311867244.242837.png 1311867244.233028 depth/1311867244.233028.png
1311867244.274849 rgb/1311867244.274849.png 1311867244.264902 depth/1311867244.264902.png
1311867244.311019 rgb/1311867244.311019.png 1311867244.301031 depth/1311867244.301031.png
1311867244.342945 rgb/1311867244.342945.png 1311867244.335519 depth/1311867244.335519.png
1311867244.374807 rgb/1311867244.374807.png 1311867244.364908 depth/1311867244.364908.png
1311867244.410917 rgb/1311867244.410917.png 1311867244.400876 depth/1311867244.400876.png
1311867244.442939 rgb/1311867244.442939.png 1311867244.432994 depth/1311867244.432994.png
1311867244.474845 rgb/1311867244.474845.png 1311867244.465451 depth/1311867244.465451.png
1311867244.510909 rgb/1311867244.510909.png 1311867244.505249 depth/1311867244.505249.png
1311867244.543087 rgb/1311867244.543087.png 1311867244.533099 depth/1311867244.533099.png
1311867244.574880 rgb/1311867244.574880.png 1311867244.566940 depth/1311867244.566940.png
1311867244.610794 rgb/1311867244.610794.png 1311867244.602703 depth/1311867244.602703.png
1311867244.642828 rgb/1311867244.642828.png 1311867244.632802 depth/1311867244.632802.png
1311867244.674838 rgb/1311867244.674838.png 1311867244.667245 depth/1311867244.667245.png
1311867244.710970 rgb/1311867244.710970.png 1311867244.701260 depth/1311867244.701260.png
1311867244.742796 rgb/1311867244.742796.png 1311867244.734632 depth/1311867244.734632.png
1311867244.774974 rgb/1311867244.774974.png 1311867244.765000 depth/1311867244.765000.png
1311867244.810910 rgb/1311867244.810910.png 1311867244.801532 depth/1311867244.801532.png
1311867244.842820 rgb/1311867244.842820.png 1311867244.833191 depth/1311867244.833191.png
1311867244.874902 rgb/1311867244.874902.png 1311867244.865157 depth/1311867244.865157.png
1311867244.910805 rgb/1311867244.910805.png 1311867244.901355 depth/1311867244.901355.png
1311867244.942839 rgb/1311867244.942839.png 1311867244.932874 depth/1311867244.932874.png
1311867244.974988 rgb/1311867244.974988.png 1311867244.965251 depth/1311867244.965251.png
1311867245.010872 rgb/1311867245.010872.png 1311867245.002272 depth/1311867245.002272.png
1311867245.042993 rgb/1311867245.042993.png 1311867245.034998 depth/1311867245.034998.png
1311867245.074920 rgb/1311867245.074920.png 1311867245.066473 depth/1311867245.066473.png
1311867245.111116 rgb/1311867245.111116.png 1311867245.104164 depth/1311867245.104164.png
1311867245.142920 rgb/1311867245.142920.png 1311867245.133805 depth/1311867245.133805.png
1311867245.174913 rgb/1311867245.174913.png 1311867245.174925 depth/1311867245.174925.png
1311867245.210898 rgb/1311867245.210898.png 1311867245.201638 depth/1311867245.201638.png
1311867245.242901 rgb/1311867245.242901.png 1311867245.234384 depth/1311867245.234384.png
1311867245.275567 rgb/1311867245.275567.png 1311867245.269269 depth/1311867245.269269.png
1311867245.312009 rgb/1311867245.312009.png 1311867245.302958 depth/1311867245.302958.png
1311867245.343010 rgb/1311867245.343010.png 1311867245.334163 depth/1311867245.334163.png
1311867245.374937 rgb/1311867245.374937.png 1311867245.372930 depth/1311867245.372930.png
1311867245.412235 rgb/1311867245.412235.png 1311867245.404540 depth/1311867245.404540.png
1311867245.442883 rgb/1311867245.442883.png 1311867245.434105 depth/1311867245.434105.png
1311867245.475145 rgb/1311867245.475145.png 1311867245.472801 depth/1311867245.472801.png
1311867245.510882 rgb/1311867245.510882.png 1311867245.500876 depth/1311867245.500876.png
1311867245.542961 rgb/1311867245.542961.png 1311867245.534361 depth/1311867245.534361.png
1311867245.574941 rgb/1311867245.574941.png 1311867245.570021 depth/1311867245.570021.png
1311867245.610913 rgb/1311867245.610913.png 1311867245.600959 depth/1311867245.600959.png
1311867245.642819 rgb/1311867245.642819.png 1311867245.633731 depth/1311867245.633731.png
1311867245.675175 rgb/1311867245.675175.png 1311867245.670091 depth/1311867245.670091.png
1311867245.710917 rgb/1311867245.710917.png 1311867245.702934 depth/1311867245.702934.png
1311867245.742982 rgb/1311867245.742982.png 1311867245.734221 depth/1311867245.734221.png
1311867245.775252 rgb/1311867245.775252.png 1311867245.772283 depth/1311867245.772283.png
1311867245.811035 rgb/1311867245.811035.png 1311867245.802066 depth/1311867245.802066.png
1311867245.842823 rgb/1311867245.842823.png 1311867245.833304 depth/1311867245.833304.png
1311867245.875777 rgb/1311867245.875777.png 1311867245.871926 depth/1311867245.871926.png
1311867245.911075 rgb/1311867245.911075.png 1311867245.900988 depth/1311867245.900988.png
1311867245.942887 rgb/1311867245.942887.png 1311867245.933643 depth/1311867245.933643.png
1311867245.975135 rgb/1311867245.975135.png 1311867245.971155 depth/1311867245.971155.png
1311867246.011242 rgb/1311867246.011242.png 1311867246.001374 depth/1311867246.001374.png
1311867246.042923 rgb/1311867246.042923.png 1311867246.033146 depth/1311867246.033146.png
1311867246.075233 rgb/1311867246.075233.png 1311867246.069018 depth/1311867246.069018.png
1311867246.110925 rgb/1311867246.110925.png 1311867246.101828 depth/1311867246.101828.png
1311867246.143089 rgb/1311867246.143089.png 1311867246.135545 depth/1311867246.135545.png
1311867246.174981 rgb/1311867246.174981.png 1311867246.169198 depth/1311867246.169198.png
1311867246.210964 rgb/1311867246.210964.png 1311867246.205140 depth/1311867246.205140.png
1311867246.242940 rgb/1311867246.242940.png 1311867246.234735 depth/1311867246.234735.png
1311867246.275065 rgb/1311867246.275065.png 1311867246.270863 depth/1311867246.270863.png
1311867246.310872 rgb/1311867246.310872.png 1311867246.303325 depth/1311867246.303325.png
1311867246.342932 rgb/1311867246.342932.png 1311867246.334051 depth/1311867246.334051.png
1311867246.375297 rgb/1311867246.375297.png 1311867246.373419 depth/1311867246.373419.png
1311867246.410931 rgb/1311867246.410931.png 1311867246.401213 depth/1311867246.401213.png
1311867246.443077 rgb/1311867246.443077.png 1311867246.437207 depth/1311867246.437207.png
1311867246.475133 rgb/1311867246.475133.png 1311867246.471314 depth/1311867246.471314.png
1311867246.510968 rgb/1311867246.510968.png 1311867246.502035 depth/1311867246.502035.png
1311867246.543113 rgb/1311867246.543113.png 1311867246.537040 depth/1311867246.537040.png
1311867246.575204 rgb/1311867246.575204.png 1311867246.571977 depth/1311867246.571977.png
1311867246.611125 rgb/1311867246.611125.png 1311867246.603266 depth/1311867246.603266.png
1311867246.643187 rgb/1311867246.643187.png 1311867246.638693 depth/1311867246.638693.png
1311867246.675169 rgb/1311867246.675169.png 1311867246.669333 depth/1311867246.669333.png
1311867246.711056 rgb/1311867246.711056.png 1311867246.704390 depth/1311867246.704390.png
1311867246.743305 rgb/1311867246.743305.png 1311867246.737272 depth/1311867246.737272.png
1311867246.774986 rgb/1311867246.774986.png 1311867246.769448 depth/1311867246.769448.png
1311867246.811193 rgb/1311867246.811193.png 1311867246.803849 depth/1311867246.803849.png
1311867246.843092 rgb/1311867246.843092.png 1311867246.838322 depth/1311867246.838322.png
1311867246.875078 rgb/1311867246.875078.png 1311867246.871268 depth/1311867246.871268.png
1311867246.911155 rgb/1311867246.911155.png 1311867246.904146 depth/1311867246.904146.png
1311867246.943061 rgb/1311867246.943061.png 1311867246.937355 depth/1311867246.937355.png
1311867246.975124 rgb/1311867246.975124.png 1311867246.972553 depth/1311867246.972553.png
1311867247.010909 rgb/1311867247.010909.png 1311867247.002134 depth/1311867247.002134.png
1311867247.044073 rgb/1311867247.044073.png 1311867247.041778 depth/1311867247.041778.png
1311867247.075192 rgb/1311867247.075192.png 1311867247.069851 depth/1311867247.069851.png
1311867247.111215 rgb/1311867247.111215.png 1311867247.101177 depth/1311867247.101177.png
1311867247.143044 rgb/1311867247.143044.png 1311867247.137342 depth/1311867247.137342.png
1311867247.175163 rgb/1311867247.175163.png 1311867247.169484 depth/1311867247.169484.png
1311867247.211319 rgb/1311867247.211319.png 1311867247.202060 depth/1311867247.202060.png
1311867247.243728 rgb/1311867247.243728.png 1311867247.239668 depth/1311867247.239668.png
1311867247.277719 rgb/1311867247.277719.png 1311867247.272079 depth/1311867247.272079.png
1311867247.310969 rgb/1311867247.310969.png 1311867247.301275 depth/1311867247.301275.png
1311867247.343205 rgb/1311867247.343205.png 1311867247.337565 depth/1311867247.337565.png
1311867247.375307 rgb/1311867247.375307.png 1311867247.369517 depth/1311867247.369517.png
1311867247.411675 rgb/1311867247.411675.png 1311867247.405433 depth/1311867247.405433.png
1311867247.444093 rgb/1311867247.444093.png 1311867247.438549 depth/1311867247.438549.png
1311867247.475103 rgb/1311867247.475103.png 1311867247.474843 depth/1311867247.474843.png
1311867247.511045 rgb/1311867247.511045.png 1311867247.501403 depth/1311867247.501403.png
1311867247.543085 rgb/1311867247.543085.png 1311867247.539732 depth/1311867247.539732.png
1311867247.575121 rgb/1311867247.575121.png 1311867247.569156 depth/1311867247.569156.png
1311867247.611460 rgb/1311867247.611460.png 1311867247.602480 depth/1311867247.602480.png
1311867247.643111 rgb/1311867247.643111.png 1311867247.638073 depth/1311867247.638073.png
1311867247.675076 rgb/1311867247.675076.png 1311867247.670014 depth/1311867247.670014.png
1311867247.711237 rgb/1311867247.711237.png 1311867247.706162 depth/1311867247.706162.png
1311867247.743122 rgb/1311867247.743122.png 1311867247.738313 depth/1311867247.738313.png
1311867247.775041 rgb/1311867247.775041.png 1311867247.773083 depth/1311867247.773083.png
1311867247.811163 rgb/1311867247.811163.png 1311867247.805402 depth/1311867247.805402.png
1311867247.843889 rgb/1311867247.843889.png 1311867247.837557 depth/1311867247.837557.png
1311867247.875244 rgb/1311867247.875244.png 1311867247.869021 depth/1311867247.869021.png
1311867247.911329 rgb/1311867247.911329.png 1311867247.907491 depth/1311867247.907491.png
1311867247.943062 rgb/1311867247.943062.png 1311867247.937547 depth/1311867247.937547.png
1311867247.976983 rgb/1311867247.976983.png 1311867247.970753 depth/1311867247.970753.png
1311867248.010991 rgb/1311867248.010991.png 1311867248.005384 depth/1311867248.005384.png
1311867248.043197 rgb/1311867248.043197.png 1311867248.037825 depth/1311867248.037825.png
1311867248.075142 rgb/1311867248.075142.png 1311867248.069890 depth/1311867248.069890.png
1311867248.112183 rgb/1311867248.112183.png 1311867248.108154 depth/1311867248.108154.png
1311867248.143172 rgb/1311867248.143172.png 1311867248.138760 depth/1311867248.138760.png
1311867248.175750 rgb/1311867248.175750.png 1311867248.169866 depth/1311867248.169866.png
1311867248.211186 rgb/1311867248.211186.png 1311867248.206824 depth/1311867248.206824.png
1311867248.243143 rgb/1311867248.243143.png 1311867248.238348 depth/1311867248.238348.png
1311867248.275529 rgb/1311867248.275529.png 1311867248.270402 depth/1311867248.270402.png
1311867248.311223 rgb/1311867248.311223.png 1311867248.308733 depth/1311867248.308733.png
1311867248.343459 rgb/1311867248.343459.png 1311867248.340448 depth/1311867248.340448.png
1311867248.375222 rgb/1311867248.375222.png 1311867248.369871 depth/1311867248.369871.png
1311867248.411556 rgb/1311867248.411556.png 1311867248.409835 depth/1311867248.409835.png
1311867248.443137 rgb/1311867248.443137.png 1311867248.438581 depth/1311867248.438581.png
1311867248.475923 rgb/1311867248.475923.png 1311867248.470199 depth/1311867248.470199.png
1311867248.511151 rgb/1311867248.511151.png 1311867248.508337 depth/1311867248.508337.png
1311867248.543189 rgb/1311867248.543189.png 1311867248.537785 depth/1311867248.537785.png
1311867248.575187 rgb/1311867248.575187.png 1311867248.572499 depth/1311867248.572499.png
1311867248.611439 rgb/1311867248.611439.png 1311867248.607009 depth/1311867248.607009.png
1311867248.643245 rgb/1311867248.643245.png 1311867248.638469 depth/1311867248.638469.png
1311867248.675309 rgb/1311867248.675309.png 1311867248.670252 depth/1311867248.670252.png
1311867248.711283 rgb/1311867248.711283.png 1311867248.706536 depth/1311867248.706536.png
1311867248.743299 rgb/1311867248.743299.png 1311867248.743305 depth/1311867248.743305.png
1311867248.776222 rgb/1311867248.776222.png 1311867248.769433 depth/1311867248.769433.png
1311867248.811190 rgb/1311867248.811190.png 1311867248.805206 depth/1311867248.805206.png
1311867248.843319 rgb/1311867248.843319.png 1311867248.838326 depth/1311867248.838326.png
1311867248.875531 rgb/1311867248.875531.png 1311867248.875524 depth/1311867248.875524.png
1311867248.911170 rgb/1311867248.911170.png 1311867248.909044 depth/1311867248.909044.png
1311867248.943097 rgb/1311867248.943097.png 1311867248.940181 depth/1311867248.940181.png
1311867248.976589 rgb/1311867248.976589.png 1311867248.976607 depth/1311867248.976607.png
1311867249.011260 rgb/1311867249.011260.png 1311867249.005328 depth/1311867249.005328.png
1311867249.043231 rgb/1311867249.043231.png 1311867249.037121 depth/1311867249.037121.png
1311867249.079906 rgb/1311867249.079906.png 1311867249.079925 depth/1311867249.079925.png
1311867249.112055 rgb/1311867249.112055.png 1311867249.106357 depth/1311867249.106357.png
1311867249.143598 rgb/1311867249.143598.png 1311867249.140147 depth/1311867249.140147.png
1311867249.178513 rgb/1311867249.178513.png 1311867249.174028 depth/1311867249.174028.png
1311867249.211358 rgb/1311867249.211358.png 1311867249.207514 depth/1311867249.207514.png
1311867249.243278 rgb/1311867249.243278.png 1311867249.239832 depth/1311867249.239832.png
1311867249.277340 rgb/1311867249.277340.png 1311867249.277356 depth/1311867249.277356.png
1311867249.311292 rgb/1311867249.311292.png 1311867249.306356 depth/1311867249.306356.png
1311867249.343725 rgb/1311867249.343725.png 1311867249.341224 depth/1311867249.341224.png
1311867249.376845 rgb/1311867249.376845.png 1311867249.376858 depth/1311867249.376858.png
1311867249.411217 rgb/1311867249.411217.png 1311867249.405473 depth/1311867249.405473.png
1311867249.443221 rgb/1311867249.443221.png 1311867249.438211 depth/1311867249.438211.png
1311867249.476410 rgb/1311867249.476410.png 1311867249.476444 depth/1311867249.476444.png
1311867249.511134 rgb/1311867249.511134.png 1311867249.505517 depth/1311867249.505517.png
1311867249.543230 rgb/1311867249.543230.png 1311867249.537314 depth/1311867249.537314.png
1311867249.575910 rgb/1311867249.575910.png 1311867249.575982 depth/1311867249.575982.png
1311867249.611223 rgb/1311867249.611223.png 1311867249.608851 depth/1311867249.608851.png
1311867249.643378 rgb/1311867249.643378.png 1311867249.638062 depth/1311867249.638062.png
1311867249.675103 rgb/1311867249.675103.png 1311867249.673702 depth/1311867249.673702.png
1311867249.711139 rgb/1311867249.711139.png 1311867249.707998 depth/1311867249.707998.png
1311867249.743247 rgb/1311867249.743247.png 1311867249.740043 depth/1311867249.740043.png
1311867249.775158 rgb/1311867249.775158.png 1311867249.773386 depth/1311867249.773386.png
1311867249.811149 rgb/1311867249.811149.png 1311867249.808523 depth/1311867249.808523.png
1311867249.843325 rgb/1311867249.843325.png 1311867249.837680 depth/1311867249.837680.png
1311867249.878395 rgb/1311867249.878395.png 1311867249.878409 depth/1311867249.878409.png
1311867249.911240 rgb/1311867249.911240.png 1311867249.907597 depth/1311867249.907597.png
1311867249.943277 rgb/1311867249.943277.png 1311867249.939728 depth/1311867249.939728.png
1311867249.975170 rgb/1311867249.975170.png 1311867249.974895 depth/1311867249.974895.png
1311867250.011711 rgb/1311867250.011711.png 1311867250.005565 depth/1311867250.005565.png
1311867250.043427 rgb/1311867250.043427.png 1311867250.037222 depth/1311867250.037222.png
1311867250.076673 rgb/1311867250.076673.png 1311867250.076719 depth/1311867250.076719.png
1311867250.111610 rgb/1311867250.111610.png 1311867250.106894 depth/1311867250.106894.png
1311867250.143222 rgb/1311867250.143222.png 1311867250.141178 depth/1311867250.141178.png
1311867250.175891 rgb/1311867250.175891.png 1311867250.175898 depth/1311867250.175898.png
1311867250.213337 rgb/1311867250.213337.png 1311867250.205522 depth/1311867250.205522.png
1311867250.245669 rgb/1311867250.245669.png 1311867250.245713 depth/1311867250.245713.png
1311867250.275168 rgb/1311867250.275168.png 1311867250.273671 depth/1311867250.273671.png
1311867250.311441 rgb/1311867250.311441.png 1311867250.305683 depth/1311867250.305683.png
1311867250.343197 rgb/1311867250.343197.png 1311867250.341283 depth/1311867250.341283.png
1311867250.378064 rgb/1311867250.378064.png 1311867250.377626 depth/1311867250.377626.png
1311867250.411649 rgb/1311867250.411649.png 1311867250.405413 depth/1311867250.405413.png
1311867250.444170 rgb/1311867250.444170.png 1311867250.444178 depth/1311867250.444178.png
1311867250.479325 rgb/1311867250.479325.png 1311867250.476408 depth/1311867250.476408.png
1311867250.511322 rgb/1311867250.511322.png 1311867250.506725 depth/1311867250.506725.png
1311867250.544330 rgb/1311867250.544330.png 1311867250.544340 depth/1311867250.544340.png
1311867250.579349 rgb/1311867250.579349.png 1311867250.573296 depth/1311867250.573296.png
1311867250.611488 rgb/1311867250.611488.png 1311867250.605223 depth/1311867250.605223.png
1311867250.643376 rgb/1311867250.643376.png 1311867250.642715 depth/1311867250.642715.png
1311867250.679554 rgb/1311867250.679554.png 1311867250.673238 depth/1311867250.673238.png
1311867250.711292 rgb/1311867250.711292.png 1311867250.707638 depth/1311867250.707638.png
1311867250.744545 rgb/1311867250.744545.png 1311867250.744589 depth/1311867250.744589.png
1311867250.779283 rgb/1311867250.779283.png 1311867250.777367 depth/1311867250.777367.png
1311867250.814558 rgb/1311867250.814558.png 1311867250.806271 depth/1311867250.806271.png
1311867250.843347 rgb/1311867250.843347.png 1311867250.843360 depth/1311867250.843360.png
1311867250.879276 rgb/1311867250.879276.png 1311867250.873642 depth/1311867250.873642.png
1311867250.911636 rgb/1311867250.911636.png 1311867250.905565 depth/1311867250.905565.png
1311867250.943372 rgb/1311867250.943372.png 1311867250.941647 depth/1311867250.941647.png
1311867250.979305 rgb/1311867250.979305.png 1311867250.976372 depth/1311867250.976372.png
1311867251.011246 rgb/1311867251.011246.png 1311867251.005419 depth/1311867251.005419.png
1311867251.043774 rgb/1311867251.043774.png 1311867251.043791 depth/1311867251.043791.png
1311867251.079316 rgb/1311867251.079316.png 1311867251.073693 depth/1311867251.073693.png
1311867251.111584 rgb/1311867251.111584.png 1311867251.105746 depth/1311867251.105746.png
1311867251.143281 rgb/1311867251.143281.png 1311867251.141746 depth/1311867251.141746.png
1311867251.179425 rgb/1311867251.179425.png 1311867251.173562 depth/1311867251.173562.png
1311867251.211383 rgb/1311867251.211383.png 1311867251.205968 depth/1311867251.205968.png
1311867251.247232 rgb/1311867251.247232.png 1311867251.246582 depth/1311867251.246582.png
1311867251.279370 rgb/1311867251.279370.png 1311867251.275047 depth/1311867251.275047.png
1311867251.313387 rgb/1311867251.313387.png 1311867251.310926 depth/1311867251.310926.png
1311867251.343242 rgb/1311867251.343242.png 1311867251.341515 depth/1311867251.341515.png
1311867251.380182 rgb/1311867251.380182.png 1311867251.376153 depth/1311867251.376153.png
1311867251.411345 rgb/1311867251.411345.png 1311867251.411355 depth/1311867251.411355.png
1311867251.443379 rgb/1311867251.443379.png 1311867251.443396 depth/1311867251.443396.png
1311867251.479338 rgb/1311867251.479338.png 1311867251.476359 depth/1311867251.476359.png
1311867251.513641 rgb/1311867251.513641.png 1311867251.517510 depth/1311867251.517510.png
1311867251.543175 rgb/1311867251.543175.png 1311867251.542053 depth/1311867251.542053.png
1311867251.579534 rgb/1311867251.579534.png 1311867251.573838 depth/1311867251.573838.png
1311867251.611953 rgb/1311867251.611953.png 1311867251.611968 depth/1311867251.611968.png
1311867251.643296 rgb/1311867251.643296.png 1311867251.641726 depth/1311867251.641726.png
1311867251.679728 rgb/1311867251.679728.png 1311867251.675240 depth/1311867251.675240.png
1311867251.712294 rgb/1311867251.712294.png 1311867251.712338 depth/1311867251.712338.png
1311867251.743499 rgb/1311867251.743499.png 1311867251.741376 depth/1311867251.741376.png
1311867251.779744 rgb/1311867251.779744.png 1311867251.773506 depth/1311867251.773506.png
1311867251.811253 rgb/1311867251.811253.png 1311867251.809288 depth/1311867251.809288.png
1311867251.843328 rgb/1311867251.843328.png 1311867251.841161 depth/1311867251.841161.png
1311867251.880542 rgb/1311867251.880542.png 1311867251.873150 depth/1311867251.873150.png
1311867251.911249 rgb/1311867251.911249.png 1311867251.909214 depth/1311867251.909214.png
1311867251.943218 rgb/1311867251.943218.png 1311867251.941809 depth/1311867251.941809.png
1311867251.980011 rgb/1311867251.980011.png 1311867251.974636 depth/1311867251.974636.png
1311867252.011886 rgb/1311867252.011886.png 1311867252.011904 depth/1311867252.011904.png
1311867252.044103 rgb/1311867252.044103.png 1311867252.041228 depth/1311867252.041228.png
1311867252.079454 rgb/1311867252.079454.png 1311867252.073278 depth/1311867252.073278.png
1311867252.112225 rgb/1311867252.112225.png 1311867252.112246 depth/1311867252.112246.png
1311867252.143295 rgb/1311867252.143295.png 1311867252.141274 depth/1311867252.141274.png
1311867252.179436 rgb/1311867252.179436.png 1311867252.173384 depth/1311867252.173384.png
1311867252.211346 rgb/1311867252.211346.png 1311867252.210777 depth/1311867252.210777.png
1311867252.243281 rgb/1311867252.243281.png 1311867252.241230 depth/1311867252.241230.png
1311867252.279411 rgb/1311867252.279411.png 1311867252.273848 depth/1311867252.273848.png
1311867252.311267 rgb/1311867252.311267.png 1311867252.311029 depth/1311867252.311029.png
1311867252.345029 rgb/1311867252.345029.png 1311867252.341880 depth/1311867252.341880.png
1311867252.379459 rgb/1311867252.379459.png 1311867252.374830 depth/1311867252.374830.png
1311867252.411197 rgb/1311867252.411197.png 1311867252.410210 depth/1311867252.410210.png
1311867252.445597 rgb/1311867252.445597.png 1311867252.445605 depth/1311867252.445605.png
1311867252.479290 rgb/1311867252.479290.png 1311867252.473786 depth/1311867252.473786.png
1311867252.511225 rgb/1311867252.511225.png 1311867252.509912 depth/1311867252.509912.png
1311867252.543282 rgb/1311867252.543282.png 1311867252.541490 depth/1311867252.541490.png
1311867252.579180 rgb/1311867252.579180.png 1311867252.578390 depth/1311867252.578390.png
1311867252.611280 rgb/1311867252.611280.png 1311867252.609663 depth/1311867252.609663.png
1311867252.643277 rgb/1311867252.643277.png 1311867252.641820 depth/1311867252.641820.png
1311867252.679249 rgb/1311867252.679249.png 1311867252.677772 depth/1311867252.677772.png
1311867252.711249 rgb/1311867252.711249.png 1311867252.710032 depth/1311867252.710032.png
1311867252.743241 rgb/1311867252.743241.png 1311867252.742726 depth/1311867252.742726.png
1311867252.779273 rgb/1311867252.779273.png 1311867252.777754 depth/1311867252.777754.png
1311867252.811278 rgb/1311867252.811278.png 1311867252.809777 depth/1311867252.809777.png
1311867252.843319 rgb/1311867252.843319.png 1311867252.841481 depth/1311867252.841481.png
1311867252.879266 rgb/1311867252.879266.png 1311867252.877640 depth/1311867252.877640.png
1311867252.911219 rgb/1311867252.911219.png 1311867252.910265 depth/1311867252.910265.png
1311867252.944692 rgb/1311867252.944692.png 1311867252.941823 depth/1311867252.941823.png
1311867252.980602 rgb/1311867252.980602.png 1311867252.977263 depth/1311867252.977263.png
1311867253.011381 rgb/1311867253.011381.png 1311867253.010849 depth/1311867253.010849.png
1311867253.043431 rgb/1311867253.043431.png 1311867253.042352 depth/1311867253.042352.png
1311867253.079921 rgb/1311867253.079921.png 1311867253.079930 depth/1311867253.079930.png
1311867253.111303 rgb/1311867253.111303.png 1311867253.109702 depth/1311867253.109702.png
1311867253.144056 rgb/1311867253.144056.png 1311867253.144076 depth/1311867253.144076.png
1311867253.179405 rgb/1311867253.179405.png 1311867253.177662 depth/1311867253.177662.png
1311867253.211216 rgb/1311867253.211216.png 1311867253.209393 depth/1311867253.209393.png
1311867253.245841 rgb/1311867253.245841.png 1311867253.242864 depth/1311867253.242864.png
1311867253.279395 rgb/1311867253.279395.png 1311867253.278709 depth/1311867253.278709.png
1311867253.311408 rgb/1311867253.311408.png 1311867253.309589 depth/1311867253.309589.png
1311867253.344521 rgb/1311867253.344521.png 1311867253.344561 depth/1311867253.344561.png
1311867253.379408 rgb/1311867253.379408.png 1311867253.377918 depth/1311867253.377918.png
1311867253.412926 rgb/1311867253.412926.png 1311867253.412953 depth/1311867253.412953.png
1311867253.444491 rgb/1311867253.444491.png 1311867253.444499 depth/1311867253.444499.png
1311867253.480478 rgb/1311867253.480478.png 1311867253.480486 depth/1311867253.480486.png
1311867253.511374 rgb/1311867253.511374.png 1311867253.509709 depth/1311867253.509709.png
1311867253.544163 rgb/1311867253.544163.png 1311867253.541739 depth/1311867253.541739.png
1311867253.579407 rgb/1311867253.579407.png 1311867253.577655 depth/1311867253.577655.png
1311867253.611802 rgb/1311867253.611802.png 1311867253.609458 depth/1311867253.609458.png
1311867253.644463 rgb/1311867253.644463.png 1311867253.644765 depth/1311867253.644765.png
1311867253.679979 rgb/1311867253.679979.png 1311867253.677508 depth/1311867253.677508.png
1311867253.711529 rgb/1311867253.711529.png 1311867253.711577 depth/1311867253.711577.png
1311867253.743537 rgb/1311867253.743537.png 1311867253.741691 depth/1311867253.741691.png
1311867253.780402 rgb/1311867253.780402.png 1311867253.780615 depth/1311867253.780615.png
1311867253.811301 rgb/1311867253.811301.png 1311867253.810444 depth/1311867253.810444.png
1311867253.846601 rgb/1311867253.846601.png 1311867253.846956 depth/1311867253.846956.png
1311867253.879206 rgb/1311867253.879206.png 1311867253.878390 depth/1311867253.878390.png
1311867253.911446 rgb/1311867253.911446.png 1311867253.909536 depth/1311867253.909536.png
1311867253.946104 rgb/1311867253.946104.png 1311867253.946160 depth/1311867253.946160.png
1311867253.979415 rgb/1311867253.979415.png 1311867253.977869 depth/1311867253.977869.png
1311867254.011966 rgb/1311867254.011966.png 1311867254.011998 depth/1311867254.011998.png
1311867254.045767 rgb/1311867254.045767.png 1311867254.045775 depth/1311867254.045775.png
1311867254.079374 rgb/1311867254.079374.png 1311867254.077738 depth/1311867254.077738.png
1311867254.111352 rgb/1311867254.111352.png 1311867254.109657 depth/1311867254.109657.png
1311867254.147685 rgb/1311867254.147685.png 1311867254.147695 depth/1311867254.147695.png
1311867254.179513 rgb/1311867254.179513.png 1311867254.177744 depth/1311867254.177744.png
1311867254.211494 rgb/1311867254.211494.png 1311867254.209721 depth/1311867254.209721.png
1311867254.246904 rgb/1311867254.246904.png 1311867254.246916 depth/1311867254.246916.png
1311867254.279857 rgb/1311867254.279857.png 1311867254.278806 depth/1311867254.278806.png
1311867254.311463 rgb/1311867254.311463.png 1311867254.309669 depth/1311867254.309669.png
1311867254.347540 rgb/1311867254.347540.png 1311867254.347559 depth/1311867254.347559.png
1311867254.379449 rgb/1311867254.379449.png 1311867254.377658 depth/1311867254.377658.png
1311867254.411535 rgb/1311867254.411535.png 1311867254.410412 depth/1311867254.410412.png
1311867254.448323 rgb/1311867254.448323.png 1311867254.448344 depth/1311867254.448344.png
1311867254.479448 rgb/1311867254.479448.png 1311867254.477669 depth/1311867254.477669.png
1311867254.511443 rgb/1311867254.511443.png 1311867254.509518 depth/1311867254.509518.png
1311867254.550046 rgb/1311867254.550046.png 1311867254.549299 depth/1311867254.549299.png
1311867254.579487 rgb/1311867254.579487.png 1311867254.577488 depth/1311867254.577488.png
1311867254.611481 rgb/1311867254.611481.png 1311867254.609387 depth/1311867254.609387.png
1311867254.645227 rgb/1311867254.645227.png 1311867254.645293 depth/1311867254.645293.png
1311867254.679490 rgb/1311867254.679490.png 1311867254.677379 depth/1311867254.677379.png
1311867254.711323 rgb/1311867254.711323.png 1311867254.710256 depth/1311867254.710256.png
1311867254.745273 rgb/1311867254.745273.png 1311867254.745333 depth/1311867254.745333.png
1311867254.779465 rgb/1311867254.779465.png 1311867254.777416 depth/1311867254.777416.png
1311867254.811574 rgb/1311867254.811574.png 1311867254.809383 depth/1311867254.809383.png
1311867254.848265 rgb/1311867254.848265.png 1311867254.848278 depth/1311867254.848278.png
1311867254.879491 rgb/1311867254.879491.png 1311867254.879292 depth/1311867254.879292.png
1311867254.913881 rgb/1311867254.913881.png 1311867254.913893 depth/1311867254.913893.png
1311867254.949070 rgb/1311867254.949070.png 1311867254.949076 depth/1311867254.949076.png
1311867254.981925 rgb/1311867254.981925.png 1311867254.981958 depth/1311867254.981958.png
1311867255.015430 rgb/1311867255.015430.png 1311867255.015436 depth/1311867255.015436.png
1311867255.049418 rgb/1311867255.049418.png 1311867255.049438 depth/1311867255.049438.png
1311867255.082194 rgb/1311867255.082194.png 1311867255.082208 depth/1311867255.082208.png
1311867255.117684 rgb/1311867255.117684.png 1311867255.117586 depth/1311867255.117586.png
1311867255.151015 rgb/1311867255.151015.png 1311867255.150610 depth/1311867255.150610.png
1311867255.183783 rgb/1311867255.183783.png 1311867255.183880 depth/1311867255.183880.png
1311867255.216913 rgb/1311867255.216913.png 1311867255.216913 depth/1311867255.216913.png
1311867255.245906 rgb/1311867255.245906.png 1311867255.245937 depth/1311867255.245937.png
1311867255.279366 rgb/1311867255.279366.png 1311867255.279172 depth/1311867255.279172.png
1311867255.313847 rgb/1311867255.313847.png 1311867255.313863 depth/1311867255.313863.png
1311867255.346831 rgb/1311867255.346831.png 1311867255.346841 depth/1311867255.346841.png
1311867255.379475 rgb/1311867255.379475.png 1311867255.377963 depth/1311867255.377963.png
1311867255.413757 rgb/1311867255.413757.png 1311867255.413764 depth/1311867255.413764.png
1311867255.445540 rgb/1311867255.445540.png 1311867255.445553 depth/1311867255.445553.png
1311867255.479482 rgb/1311867255.479482.png 1311867255.478153 depth/1311867255.478153.png
1311867255.515585 rgb/1311867255.515585.png 1311867255.515610 depth/1311867255.515610.png
1311867255.545730 rgb/1311867255.545730.png 1311867255.545778 depth/1311867255.545778.png
1311867255.579442 rgb/1311867255.579442.png 1311867255.578444 depth/1311867255.578444.png
1311867255.615323 rgb/1311867255.615323.png 1311867255.615333 depth/1311867255.615333.png
1311867255.645642 rgb/1311867255.645642.png 1311867255.645648 depth/1311867255.645648.png
1311867255.680081 rgb/1311867255.680081.png 1311867255.680102 depth/1311867255.680102.png
1311867255.718269 rgb/1311867255.718269.png 1311867255.718292 depth/1311867255.718292.png
1311867255.745767 rgb/1311867255.745767.png 1311867255.745775 depth/1311867255.745775.png
1311867255.780996 rgb/1311867255.780996.png 1311867255.781093 depth/1311867255.781093.png
1311867255.817593 rgb/1311867255.817593.png 1311867255.817610 depth/1311867255.817610.png
1311867255.845687 rgb/1311867255.845687.png 1311867255.845725 depth/1311867255.845725.png
1311867255.879379 rgb/1311867255.879379.png 1311867255.878755 depth/1311867255.878755.png
1311867255.914024 rgb/1311867255.914024.png 1311867255.914031 depth/1311867255.914031.png
1311867255.945901 rgb/1311867255.945901.png 1311867255.945908 depth/1311867255.945908.png
1311867255.979486 rgb/1311867255.979486.png 1311867255.977784 depth/1311867255.977784.png
1311867256.017783 rgb/1311867256.017783.png 1311867256.017797 depth/1311867256.017797.png
1311867256.046004 rgb/1311867256.046004.png 1311867256.046014 depth/1311867256.046014.png
1311867256.079590 rgb/1311867256.079590.png 1311867256.085688 depth/1311867256.085688.png
1311867256.116730 rgb/1311867256.116730.png 1311867256.116497 depth/1311867256.116497.png
1311867256.145219 rgb/1311867256.145219.png 1311867256.145227 depth/1311867256.145227.png
1311867256.179506 rgb/1311867256.179506.png 1311867256.177549 depth/1311867256.177549.png
1311867256.217737 rgb/1311867256.217737.png 1311867256.217749 depth/1311867256.217749.png
1311867256.245462 rgb/1311867256.245462.png 1311867256.245469 depth/1311867256.245469.png
1311867256.284698 rgb/1311867256.284698.png 1311867256.284704 depth/1311867256.284704.png
1311867256.314334 rgb/1311867256.314334.png 1311867256.314342 depth/1311867256.314342.png
1311867256.347169 rgb/1311867256.347169.png 1311867256.347179 depth/1311867256.347179.png
1311867256.384803 rgb/1311867256.384803.png 1311867256.384865 depth/1311867256.384865.png
1311867256.415853 rgb/1311867256.415853.png 1311867256.415865 depth/1311867256.415865.png
1311867256.445283 rgb/1311867256.445283.png 1311867256.445284 depth/1311867256.445284.png
1311867256.484375 rgb/1311867256.484375.png 1311867256.484460 depth/1311867256.484460.png
1311867256.513577 rgb/1311867256.513577.png 1311867256.513583 depth/1311867256.513583.png
1311867256.547861 rgb/1311867256.547861.png 1311867256.547879 depth/1311867256.547879.png
1311867256.583591 rgb/1311867256.583591.png 1311867256.583649 depth/1311867256.583649.png
1311867256.616028 rgb/1311867256.616028.png 1311867256.616037 depth/1311867256.616037.png
1311867256.645225 rgb/1311867256.645225.png 1311867256.645231 depth/1311867256.645231.png
1311867256.683263 rgb/1311867256.683263.png 1311867256.683276 depth/1311867256.683276.png
1311867256.714018 rgb/1311867256.714018.png 1311867256.714030 depth/1311867256.714030.png
1311867256.746329 rgb/1311867256.746329.png 1311867256.746337 depth/1311867256.746337.png
1311867256.782735 rgb/1311867256.782735.png 1311867256.782740 depth/1311867256.782740.png
1311867256.814038 rgb/1311867256.814038.png 1311867256.814043 depth/1311867256.814043.png
1311867256.847722 rgb/1311867256.847722.png 1311867256.847740 depth/1311867256.847740.png
1311867256.883890 rgb/1311867256.883890.png 1311867256.883898 depth/1311867256.883898.png
1311867256.914798 rgb/1311867256.914798.png 1311867256.914811 depth/1311867256.914811.png
1311867256.946531 rgb/1311867256.946531.png 1311867256.946538 depth/1311867256.946538.png
1311867256.981447 rgb/1311867256.981447.png 1311867256.981461 depth/1311867256.981461.png
1311867257.012988 rgb/1311867257.012988.png 1311867257.012996 depth/1311867257.012996.png
1311867257.045185 rgb/1311867257.045185.png 1311867257.045191 depth/1311867257.045191.png
1311867257.084110 rgb/1311867257.084110.png 1311867257.084137 depth/1311867257.084137.png
1311867257.113385 rgb/1311867257.113385.png 1311867257.113443 depth/1311867257.113443.png
1311867257.147422 rgb/1311867257.147422.png 1311867257.147431 depth/1311867257.147431.png
1311867257.182069 rgb/1311867257.182069.png 1311867257.182123 depth/1311867257.182123.png
1311867257.214758 rgb/1311867257.214758.png 1311867257.214784 depth/1311867257.214784.png
1311867257.245697 rgb/1311867257.245697.png 1311867257.245704 depth/1311867257.245704.png
1311867257.282412 rgb/1311867257.282412.png 1311867257.282449 depth/1311867257.282449.png
1311867257.313334 rgb/1311867257.313334.png 1311867257.313343 depth/1311867257.313343.png
1311867257.345279 rgb/1311867257.345279.png 1311867257.345285 depth/1311867257.345285.png
1311867257.383951 rgb/1311867257.383951.png 1311867257.383963 depth/1311867257.383963.png
1311867257.416062 rgb/1311867257.416062.png 1311867257.419813 depth/1311867257.419813.png
1311867257.445852 rgb/1311867257.445852.png 1311867257.445861 depth/1311867257.445861.png
1311867257.485117 rgb/1311867257.485117.png 1311867257.485127 depth/1311867257.485127.png
1311867257.516611 rgb/1311867257.516611.png 1311867257.516625 depth/1311867257.516625.png
1311867257.543702 rgb/1311867257.543702.png 1311867257.553788 depth/1311867257.553788.png
1311867257.583609 rgb/1311867257.583609.png 1311867257.583620 depth/1311867257.583620.png
1311867257.615413 rgb/1311867257.615413.png 1311867257.615446 depth/1311867257.615446.png
1311867257.643749 rgb/1311867257.643749.png 1311867257.651972 depth/1311867257.651972.png
1311867257.684241 rgb/1311867257.684241.png 1311867257.684296 depth/1311867257.684296.png
1311867257.718778 rgb/1311867257.718778.png 1311867257.714646 depth/1311867257.714646.png
1311867257.743747 rgb/1311867257.743747.png 1311867257.752781 depth/1311867257.752781.png
1311867257.783800 rgb/1311867257.783800.png 1311867257.783843 depth/1311867257.783843.png
1311867257.818099 rgb/1311867257.818099.png 1311867257.818141 depth/1311867257.818141.png
1311867257.843575 rgb/1311867257.843575.png 1311867257.853070 depth/1311867257.853070.png
1311867257.885458 rgb/1311867257.885458.png 1311867257.885405 depth/1311867257.885405.png
1311867257.915235 rgb/1311867257.915235.png 1311867257.915253 depth/1311867257.915253.png
1311867257.943765 rgb/1311867257.943765.png 1311867257.955903 depth/1311867257.955903.png
1311867257.985062 rgb/1311867257.985062.png 1311867257.985078 depth/1311867257.985078.png
1311867258.013561 rgb/1311867258.013561.png 1311867258.013571 depth/1311867258.013571.png
1311867258.043623 rgb/1311867258.043623.png 1311867258.052661 depth/1311867258.052661.png
1311867258.083652 rgb/1311867258.083652.png 1311867258.083661 depth/1311867258.083661.png
1311867258.113782 rgb/1311867258.113782.png 1311867258.113786 depth/1311867258.113786.png
1311867258.143714 rgb/1311867258.143714.png 1311867258.150107 depth/1311867258.150107.png
1311867258.184833 rgb/1311867258.184833.png 1311867258.184848 depth/1311867258.184848.png
1311867258.216268 rgb/1311867258.216268.png 1311867258.216273 depth/1311867258.216273.png
1311867258.243624 rgb/1311867258.243624.png 1311867258.252498 depth/1311867258.252498.png
1311867258.285010 rgb/1311867258.285010.png 1311867258.285783 depth/1311867258.285783.png
1311867258.313274 rgb/1311867258.313274.png 1311867258.313291 depth/1311867258.313291.png
1311867258.343642 rgb/1311867258.343642.png 1311867258.351071 depth/1311867258.351071.png
1311867258.381205 rgb/1311867258.381205.png 1311867258.381212 depth/1311867258.381212.png
1311867258.414263 rgb/1311867258.414263.png 1311867258.414271 depth/1311867258.414271.png
1311867258.443907 rgb/1311867258.443907.png 1311867258.450701 depth/1311867258.450701.png
1311867258.482546 rgb/1311867258.482546.png 1311867258.482606 depth/1311867258.482606.png
1311867258.513980 rgb/1311867258.513980.png 1311867258.513990 depth/1311867258.513990.png
1311867258.543595 rgb/1311867258.543595.png 1311867258.550051 depth/1311867258.550051.png
1311867258.583598 rgb/1311867258.583598.png 1311867258.583604 depth/1311867258.583604.png
1311867258.614160 rgb/1311867258.614160.png 1311867258.614168 depth/1311867258.614168.png
1311867258.643778 rgb/1311867258.643778.png 1311867258.650686 depth/1311867258.650686.png
1311867258.685220 rgb/1311867258.685220.png 1311867258.685647 depth/1311867258.685647.png
1311867258.713406 rgb/1311867258.713406.png 1311867258.713424 depth/1311867258.713424.png
1311867258.743665 rgb/1311867258.743665.png 1311867258.754356 depth/1311867258.754356.png
1311867258.784349 rgb/1311867258.784349.png 1311867258.784359 depth/1311867258.784359.png
1311867258.811690 rgb/1311867258.811690.png 1311867258.819369 depth/1311867258.819369.png
1311867258.843893 rgb/1311867258.843893.png 1311867258.851441 depth/1311867258.851441.png
1311867258.884560 rgb/1311867258.884560.png 1311867258.884601 depth/1311867258.884601.png
1311867258.911750 rgb/1311867258.911750.png 1311867258.917897 depth/1311867258.917897.png
1311867258.944000 rgb/1311867258.944000.png 1311867258.950620 depth/1311867258.950620.png
1311867258.984155 rgb/1311867258.984155.png 1311867258.984167 depth/1311867258.984167.png
1311867259.011907 rgb/1311867259.011907.png 1311867259.019439 depth/1311867259.019439.png
1311867259.043970 rgb/1311867259.043970.png 1311867259.049796 depth/1311867259.049796.png
1311867259.084547 rgb/1311867259.084547.png 1311867259.084510 depth/1311867259.084510.png
1311867259.111734 rgb/1311867259.111734.png 1311867259.118993 depth/1311867259.118993.png
1311867259.143877 rgb/1311867259.143877.png 1311867259.150603 depth/1311867259.150603.png
1311867259.183764 rgb/1311867259.183764.png 1311867259.183782 depth/1311867259.183782.png
1311867259.211951 rgb/1311867259.211951.png 1311867259.219198 depth/1311867259.219198.png
1311867259.243853 rgb/1311867259.243853.png 1311867259.253290 depth/1311867259.253290.png
1311867259.281587 rgb/1311867259.281587.png 1311867259.281598 depth/1311867259.281598.png
1311867259.311928 rgb/1311867259.311928.png 1311867259.321272 depth/1311867259.321272.png
1311867259.343762 rgb/1311867259.343762.png 1311867259.351904 depth/1311867259.351904.png
1311867259.383911 rgb/1311867259.383911.png 1311867259.384019 depth/1311867259.384019.png
1311867259.411722 rgb/1311867259.411722.png 1311867259.420429 depth/1311867259.420429.png
1311867259.443793 rgb/1311867259.443793.png 1311867259.457918 depth/1311867259.457918.png
1311867259.481615 rgb/1311867259.481615.png 1311867259.485055 depth/1311867259.485055.png
1311867259.511730 rgb/1311867259.511730.png 1311867259.518982 depth/1311867259.518982.png
1311867259.550578 rgb/1311867259.550578.png 1311867259.550593 depth/1311867259.550593.png
1311867259.582216 rgb/1311867259.582216.png 1311867259.582324 depth/1311867259.582324.png
1311867259.611739 rgb/1311867259.611739.png 1311867259.619272 depth/1311867259.619272.png
1311867259.649471 rgb/1311867259.649471.png 1311867259.649484 depth/1311867259.649484.png
1311867259.682849 rgb/1311867259.682849.png 1311867259.682859 depth/1311867259.682859.png
1311867259.711827 rgb/1311867259.711827.png 1311867259.720199 depth/1311867259.720199.png
1311867259.752007 rgb/1311867259.752007.png 1311867259.755769 depth/1311867259.755769.png
1311867259.781780 rgb/1311867259.781780.png 1311867259.781786 depth/1311867259.781786.png
1311867259.811817 rgb/1311867259.811817.png 1311867259.817701 depth/1311867259.817701.png
1311867259.850399 rgb/1311867259.850399.png 1311867259.854894 depth/1311867259.854894.png
1311867259.881835 rgb/1311867259.881835.png 1311867259.881841 depth/1311867259.881841.png
1311867259.912113 rgb/1311867259.912113.png 1311867259.921918 depth/1311867259.921918.png
1311867259.952003 rgb/1311867259.952003.png 1311867259.952013 depth/1311867259.952013.png
1311867259.979767 rgb/1311867259.979767.png 1311867259.992364 depth/1311867259.992364.png
1311867260.012691 rgb/1311867260.012691.png 1311867260.021947 depth/1311867260.021947.png
1311867260.049315 rgb/1311867260.049315.png 1311867260.049321 depth/1311867260.049321.png
1311867260.079913 rgb/1311867260.079913.png 1311867260.088808 depth/1311867260.088808.png
1311867260.111941 rgb/1311867260.111941.png 1311867260.121050 depth/1311867260.121050.png
1311867260.151371 rgb/1311867260.151371.png 1311867260.151387 depth/1311867260.151387.png
1311867260.179934 rgb/1311867260.179934.png 1311867260.190886 depth/1311867260.190886.png
1311867260.211913 rgb/1311867260.211913.png 1311867260.220444 depth/1311867260.220444.png
1311867260.249637 rgb/1311867260.249637.png 1311867260.249667 depth/1311867260.249667.png
1311867260.279865 rgb/1311867260.279865.png 1311867260.286988 depth/1311867260.286988.png
1311867260.312068 rgb/1311867260.312068.png 1311867260.319559 depth/1311867260.319559.png
1311867260.350508 rgb/1311867260.350508.png 1311867260.350526 depth/1311867260.350526.png
1311867260.380002 rgb/1311867260.380002.png 1311867260.386890 depth/1311867260.386890.png
1311867260.412000 rgb/1311867260.412000.png 1311867260.421130 depth/1311867260.421130.png
1311867260.452169 rgb/1311867260.452169.png 1311867260.452177 depth/1311867260.452177.png
1311867260.479772 rgb/1311867260.479772.png 1311867260.486747 depth/1311867260.486747.png
1311867260.512102 rgb/1311867260.512102.png 1311867260.519293 depth/1311867260.519293.png
1311867260.552766 rgb/1311867260.552766.png 1311867260.552787 depth/1311867260.552787.png
1311867260.579905 rgb/1311867260.579905.png 1311867260.588045 depth/1311867260.588045.png
1311867260.612014 rgb/1311867260.612014.png 1311867260.619619 depth/1311867260.619619.png
1311867260.649334 rgb/1311867260.649334.png 1311867260.649341 depth/1311867260.649341.png
1311867260.679860 rgb/1311867260.679860.png 1311867260.686534 depth/1311867260.686534.png
1311867260.711867 rgb/1311867260.711867.png 1311867260.718823 depth/1311867260.718823.png
1311867260.749329 rgb/1311867260.749329.png 1311867260.749337 depth/1311867260.749337.png
1311867260.780035 rgb/1311867260.780035.png 1311867260.785965 depth/1311867260.785965.png
1311867260.812146 rgb/1311867260.812146.png 1311867260.817908 depth/1311867260.817908.png
1311867260.851416 rgb/1311867260.851416.png 1311867260.851460 depth/1311867260.851460.png
1311867260.879809 rgb/1311867260.879809.png 1311867260.886743 depth/1311867260.886743.png
1311867260.912017 rgb/1311867260.912017.png 1311867260.917785 depth/1311867260.917785.png
1311867260.949439 rgb/1311867260.949439.png 1311867260.949446 depth/1311867260.949446.png
1311867260.979950 rgb/1311867260.979950.png 1311867260.986968 depth/1311867260.986968.png
1311867261.011875 rgb/1311867261.011875.png 1311867261.020226 depth/1311867261.020226.png
1311867261.051950 rgb/1311867261.051950.png 1311867261.051964 depth/1311867261.051964.png
1311867261.079805 rgb/1311867261.079805.png 1311867261.087158 depth/1311867261.087158.png
1311867261.111871 rgb/1311867261.111871.png 1311867261.119766 depth/1311867261.119766.png
1311867261.153079 rgb/1311867261.153079.png 1311867261.152864 depth/1311867261.152864.png
1311867261.179986 rgb/1311867261.179986.png 1311867261.187263 depth/1311867261.187263.png
1311867261.211987 rgb/1311867261.211987.png 1311867261.219109 depth/1311867261.219109.png
1311867261.247791 rgb/1311867261.247791.png 1311867261.254823 depth/1311867261.254823.png
1311867261.280012 rgb/1311867261.280012.png 1311867261.287960 depth/1311867261.287960.png
1311867261.312072 rgb/1311867261.312072.png 1311867261.318503 depth/1311867261.318503.png
1311867261.347781 rgb/1311867261.347781.png 1311867261.354630 depth/1311867261.354630.png
1311867261.379963 rgb/1311867261.379963.png 1311867261.385833 depth/1311867261.385833.png
1311867261.412118 rgb/1311867261.412118.png 1311867261.418638 depth/1311867261.418638.png
1311867261.448088 rgb/1311867261.448088.png 1311867261.455868 depth/1311867261.455868.png
1311867261.479857 rgb/1311867261.479857.png 1311867261.486219 depth/1311867261.486219.png
1311867261.512250 rgb/1311867261.512250.png 1311867261.517863 depth/1311867261.517863.png
1311867261.547863 rgb/1311867261.547863.png 1311867261.555652 depth/1311867261.555652.png
1311867261.579903 rgb/1311867261.579903.png 1311867261.585790 depth/1311867261.585790.png
1311867261.612131 rgb/1311867261.612131.png 1311867261.617464 depth/1311867261.617464.png
1311867261.648078 rgb/1311867261.648078.png 1311867261.665201 depth/1311867261.665201.png
1311867261.680301 rgb/1311867261.680301.png 1311867261.688993 depth/1311867261.688993.png
1311867261.712383 rgb/1311867261.712383.png 1311867261.719311 depth/1311867261.719311.png
1311867261.748085 rgb/1311867261.748085.png 1311867261.760155 depth/1311867261.760155.png
1311867261.779918 rgb/1311867261.779918.png 1311867261.787688 depth/1311867261.787688.png
1311867261.811956 rgb/1311867261.811956.png 1311867261.821394 depth/1311867261.821394.png
1311867261.848006 rgb/1311867261.848006.png 1311867261.859815 depth/1311867261.859815.png
1311867261.880073 rgb/1311867261.880073.png 1311867261.888546 depth/1311867261.888546.png
1311867261.912163 rgb/1311867261.912163.png 1311867261.921236 depth/1311867261.921236.png
1311867261.948000 rgb/1311867261.948000.png 1311867261.959230 depth/1311867261.959230.png
1311867261.980242 rgb/1311867261.980242.png 1311867261.988614 depth/1311867261.988614.png
1311867262.011962 rgb/1311867262.011962.png 1311867262.021953 depth/1311867262.021953.png
1311867262.047907 rgb/1311867262.047907.png 1311867262.057663 depth/1311867262.057663.png
1311867262.080301 rgb/1311867262.080301.png 1311867262.094468 depth/1311867262.094468.png
1311867262.117955 rgb/1311867262.117955.png 1311867262.118048 depth/1311867262.118048.png
1311867262.147860 rgb/1311867262.147860.png 1311867262.153988 depth/1311867262.153988.png
1311867262.180119 rgb/1311867262.180119.png 1311867262.190654 depth/1311867262.190654.png
1311867262.212167 rgb/1311867262.212167.png 1311867262.220062 depth/1311867262.220062.png
1311867262.247855 rgb/1311867262.247855.png 1311867262.255759 depth/1311867262.255759.png
1311867262.279909 rgb/1311867262.279909.png 1311867262.289356 depth/1311867262.289356.png
1311867262.312207 rgb/1311867262.312207.png 1311867262.319283 depth/1311867262.319283.png
1311867262.347903 rgb/1311867262.347903.png 1311867262.354351 depth/1311867262.354351.png
1311867262.379904 rgb/1311867262.379904.png 1311867262.386276 depth/1311867262.386276.png
1311867262.411961 rgb/1311867262.411961.png 1311867262.419248 depth/1311867262.419248.png
1311867262.448089 rgb/1311867262.448089.png 1311867262.457937 depth/1311867262.457937.png
1311867262.479872 rgb/1311867262.479872.png 1311867262.488291 depth/1311867262.488291.png
1311867262.512133 rgb/1311867262.512133.png 1311867262.522872 depth/1311867262.522872.png
1311867262.547912 rgb/1311867262.547912.png 1311867262.555407 depth/1311867262.555407.png
1311867262.579872 rgb/1311867262.579872.png 1311867262.587320 depth/1311867262.587320.png
1311867262.612224 rgb/1311867262.612224.png 1311867262.623551 depth/1311867262.623551.png
1311867262.647862 rgb/1311867262.647862.png 1311867262.654801 depth/1311867262.654801.png
1311867262.680238 rgb/1311867262.680238.png 1311867262.690114 depth/1311867262.690114.png
1311867262.712055 rgb/1311867262.712055.png 1311867262.723480 depth/1311867262.723480.png
1311867262.748013 rgb/1311867262.748013.png 1311867262.755088 depth/1311867262.755088.png
1311867262.780047 rgb/1311867262.780047.png 1311867262.789079 depth/1311867262.789079.png
1311867262.812118 rgb/1311867262.812118.png 1311867262.823227 depth/1311867262.823227.png
1311867262.847972 rgb/1311867262.847972.png 1311867262.856114 depth/1311867262.856114.png
1311867262.880083 rgb/1311867262.880083.png 1311867262.887828 depth/1311867262.887828.png
1311867262.912008 rgb/1311867262.912008.png 1311867262.922193 depth/1311867262.922193.png
1311867262.947979 rgb/1311867262.947979.png 1311867262.953997 depth/1311867262.953997.png
1311867262.979967 rgb/1311867262.979967.png 1311867262.987732 depth/1311867262.987732.png
1311867263.012291 rgb/1311867263.012291.png 1311867263.023844 depth/1311867263.023844.png
1311867263.048000 rgb/1311867263.048000.png 1311867263.055280 depth/1311867263.055280.png
1311867263.079930 rgb/1311867263.079930.png 1311867263.087004 depth/1311867263.087004.png
1311867263.111968 rgb/1311867263.111968.png 1311867263.122690 depth/1311867263.122690.png
1311867263.148043 rgb/1311867263.148043.png 1311867263.153708 depth/1311867263.153708.png
1311867263.180026 rgb/1311867263.180026.png 1311867263.188423 depth/1311867263.188423.png
1311867263.212088 rgb/1311867263.212088.png 1311867263.222581 depth/1311867263.222581.png
1311867263.248034 rgb/1311867263.248034.png 1311867263.253614 depth/1311867263.253614.png
1311867263.280002 rgb/1311867263.280002.png 1311867263.288447 depth/1311867263.288447.png
1311867263.312094 rgb/1311867263.312094.png 1311867263.323627 depth/1311867263.323627.png
1311867263.348120 rgb/1311867263.348120.png 1311867263.353947 depth/1311867263.353947.png
1311867263.380039 rgb/1311867263.380039.png 1311867263.385653 depth/1311867263.385653.png
1311867263.412375 rgb/1311867263.412375.png 1311867263.422146 depth/1311867263.422146.png
1311867263.448153 rgb/1311867263.448153.png 1311867263.454956 depth/1311867263.454956.png
1311867263.480018 rgb/1311867263.480018.png 1311867263.487639 depth/1311867263.487639.png
1311867263.511993 rgb/1311867263.511993.png 1311867263.523595 depth/1311867263.523595.png
1311867263.547977 rgb/1311867263.547977.png 1311867263.553510 depth/1311867263.553510.png
1311867263.580059 rgb/1311867263.580059.png 1311867263.585504 depth/1311867263.585504.png
1311867263.612205 rgb/1311867263.612205.png 1311867263.623614 depth/1311867263.623614.png
1311867263.648021 rgb/1311867263.648021.png 1311867263.654392 depth/1311867263.654392.png
1311867263.679956 rgb/1311867263.679956.png 1311867263.690378 depth/1311867263.690378.png
1311867263.712221 rgb/1311867263.712221.png 1311867263.722763 depth/1311867263.722763.png
1311867263.748100 rgb/1311867263.748100.png 1311867263.755967 depth/1311867263.755967.png
1311867263.780318 rgb/1311867263.780318.png 1311867263.791156 depth/1311867263.791156.png
1311867263.812318 rgb/1311867263.812318.png 1311867263.823519 depth/1311867263.823519.png
1311867263.848119 rgb/1311867263.848119.png 1311867263.855552 depth/1311867263.855552.png
1311867263.880150 rgb/1311867263.880150.png 1311867263.892539 depth/1311867263.892539.png
1311867263.912334 rgb/1311867263.912334.png 1311867263.925589 depth/1311867263.925589.png
1311867263.948206 rgb/1311867263.948206.png 1311867263.955721 depth/1311867263.955721.png
1311867263.979999 rgb/1311867263.979999.png 1311867263.991345 depth/1311867263.991345.png
1311867264.012231 rgb/1311867264.012231.png 1311867264.026508 depth/1311867264.026508.png
1311867264.048127 rgb/1311867264.048127.png 1311867264.053984 depth/1311867264.053984.png
1311867264.080210 rgb/1311867264.080210.png 1311867264.093584 depth/1311867264.093584.png
1311867264.112282 rgb/1311867264.112282.png 1311867264.123293 depth/1311867264.123293.png
1311867264.147983 rgb/1311867264.147983.png 1311867264.154781 depth/1311867264.154781.png
1311867264.180145 rgb/1311867264.180145.png 1311867264.190874 depth/1311867264.190874.png
1311867264.212109 rgb/1311867264.212109.png 1311867264.223044 depth/1311867264.223044.png
1311867264.248024 rgb/1311867264.248024.png 1311867264.254928 depth/1311867264.254928.png
1311867264.280169 rgb/1311867264.280169.png 1311867264.291094 depth/1311867264.291094.png
1311867264.312006 rgb/1311867264.312006.png 1311867264.322354 depth/1311867264.322354.png
1311867264.348192 rgb/1311867264.348192.png 1311867264.353971 depth/1311867264.353971.png
1311867264.380241 rgb/1311867264.380241.png 1311867264.390357 depth/1311867264.390357.png
1311867264.412214 rgb/1311867264.412214.png 1311867264.424713 depth/1311867264.424713.png
1311867264.448004 rgb/1311867264.448004.png 1311867264.453671 depth/1311867264.453671.png
1311867264.480074 rgb/1311867264.480074.png 1311867264.491122 depth/1311867264.491122.png
1311867264.512227 rgb/1311867264.512227.png 1311867264.522093 depth/1311867264.522093.png
1311867264.548155 rgb/1311867264.548155.png 1311867264.554466 depth/1311867264.554466.png
1311867264.580092 rgb/1311867264.580092.png 1311867264.591919 depth/1311867264.591919.png
1311867264.612330 rgb/1311867264.612330.png 1311867264.623954 depth/1311867264.623954.png
1311867264.648092 rgb/1311867264.648092.png 1311867264.653789 depth/1311867264.653789.png
1311867264.680199 rgb/1311867264.680199.png 1311867264.690898 depth/1311867264.690898.png
1311867264.712454 rgb/1311867264.712454.png 1311867264.722804 depth/1311867264.722804.png
1311867264.747965 rgb/1311867264.747965.png 1311867264.754714 depth/1311867264.754714.png
1311867264.780125 rgb/1311867264.780125.png 1311867264.790914 depth/1311867264.790914.png
1311867264.812115 rgb/1311867264.812115.png 1311867264.823344 depth/1311867264.823344.png
1311867264.848189 rgb/1311867264.848189.png 1311867264.854079 depth/1311867264.854079.png
1311867264.880141 rgb/1311867264.880141.png 1311867264.890441 depth/1311867264.890441.png
1311867264.912230 rgb/1311867264.912230.png 1311867264.923558 depth/1311867264.923558.png
1311867264.948186 rgb/1311867264.948186.png 1311867264.959884 depth/1311867264.959884.png
1311867264.980433 rgb/1311867264.980433.png 1311867264.991684 depth/1311867264.991684.png
1311867265.012192 rgb/1311867265.012192.png 1311867265.022003 depth/1311867265.022003.png
1311867265.048128 rgb/1311867265.048128.png 1311867265.058149 depth/1311867265.058149.png
1311867265.080210 rgb/1311867265.080210.png 1311867265.091172 depth/1311867265.091172.png
1311867265.112164 rgb/1311867265.112164.png 1311867265.121711 depth/1311867265.121711.png
1311867265.148104 rgb/1311867265.148104.png 1311867265.158209 depth/1311867265.158209.png
1311867265.180303 rgb/1311867265.180303.png 1311867265.189952 depth/1311867265.189952.png
1311867265.212300 rgb/1311867265.212300.png 1311867265.222522 depth/1311867265.222522.png
1311867265.248214 rgb/1311867265.248214.png 1311867265.258185 depth/1311867265.258185.png
1311867265.280318 rgb/1311867265.280318.png 1311867265.291513 depth/1311867265.291513.png
1311867265.312310 rgb/1311867265.312310.png 1311867265.322086 depth/1311867265.322086.png
1311867265.348200 rgb/1311867265.348200.png 1311867265.358559 depth/1311867265.358559.png
1311867265.380133 rgb/1311867265.380133.png 1311867265.391247 depth/1311867265.391247.png
1311867265.412207 rgb/1311867265.412207.png 1311867265.424453 depth/1311867265.424453.png
1311867265.448180 rgb/1311867265.448180.png 1311867265.460441 depth/1311867265.460441.png
1311867265.480231 rgb/1311867265.480231.png 1311867265.490242 depth/1311867265.490242.png
1311867265.512277 rgb/1311867265.512277.png 1311867265.523057 depth/1311867265.523057.png
1311867265.548378 rgb/1311867265.548378.png 1311867265.559452 depth/1311867265.559452.png
1311867265.580223 rgb/1311867265.580223.png 1311867265.593230 depth/1311867265.593230.png
1311867265.612065 rgb/1311867265.612065.png 1311867265.625070 depth/1311867265.625070.png
1311867265.648285 rgb/1311867265.648285.png 1311867265.661073 depth/1311867265.661073.png
1311867265.680305 rgb/1311867265.680305.png 1311867265.695601 depth/1311867265.695601.png
1311867265.712166 rgb/1311867265.712166.png 1311867265.722189 depth/1311867265.722189.png
1311867265.748225 rgb/1311867265.748225.png 1311867265.762627 depth/1311867265.762627.png
1311867265.780694 rgb/1311867265.780694.png 1311867265.792592 depth/1311867265.792592.png
1311867265.812278 rgb/1311867265.812278.png 1311867265.822421 depth/1311867265.822421.png
1311867265.848187 rgb/1311867265.848187.png 1311867265.859339 depth/1311867265.859339.png
1311867265.880193 rgb/1311867265.880193.png 1311867265.894360 depth/1311867265.894360.png
1311867265.912326 rgb/1311867265.912326.png 1311867265.925645 depth/1311867265.925645.png
1311867265.948259 rgb/1311867265.948259.png 1311867265.962098 depth/1311867265.962098.png
1311867265.980599 rgb/1311867265.980599.png 1311867265.990899 depth/1311867265.990899.png
1311867266.012180 rgb/1311867266.012180.png 1311867266.023347 depth/1311867266.023347.png
1311867266.048362 rgb/1311867266.048362.png 1311867266.063426 depth/1311867266.063426.png
1311867266.080451 rgb/1311867266.080451.png 1311867266.095464 depth/1311867266.095464.png
1311867266.112239 rgb/1311867266.112239.png 1311867266.124160 depth/1311867266.124160.png
1311867266.148464 rgb/1311867266.148464.png 1311867266.163481 depth/1311867266.163481.png
1311867266.180282 rgb/1311867266.180282.png 1311867266.192269 depth/1311867266.192269.png
1311867266.212181 rgb/1311867266.212181.png 1311867266.225520 depth/1311867266.225520.png
1311867266.248205 rgb/1311867266.248205.png 1311867266.259785 depth/1311867266.259785.png
1311867266.280227 rgb/1311867266.280227.png 1311867266.291512 depth/1311867266.291512.png
1311867266.312311 rgb/1311867266.312311.png 1311867266.325804 depth/1311867266.325804.png
1311867266.348175 rgb/1311867266.348175.png 1311867266.360155 depth/1311867266.360155.png
1311867266.380379 rgb/1311867266.380379.png 1311867266.391316 depth/1311867266.391316.png
1311867266.412323 rgb/1311867266.412323.png 1311867266.425487 depth/1311867266.425487.png
1311867266.448402 rgb/1311867266.448402.png 1311867266.461291 depth/1311867266.461291.png
1311867266.480472 rgb/1311867266.480472.png 1311867266.491260 depth/1311867266.491260.png
1311867266.512523 rgb/1311867266.512523.png 1311867266.528493 depth/1311867266.528493.png
1311867266.548233 rgb/1311867266.548233.png 1311867266.558736 depth/1311867266.558736.png
1311867266.580375 rgb/1311867266.580375.png 1311867266.590682 depth/1311867266.590682.png
1311867266.612250 rgb/1311867266.612250.png 1311867266.625647 depth/1311867266.625647.png
1311867266.648261 rgb/1311867266.648261.png 1311867266.659642 depth/1311867266.659642.png
1311867266.680311 rgb/1311867266.680311.png 1311867266.691494 depth/1311867266.691494.png
1311867266.712145 rgb/1311867266.712145.png 1311867266.726079 depth/1311867266.726079.png
1311867266.748428 rgb/1311867266.748428.png 1311867266.757624 depth/1311867266.757624.png
1311867266.780320 rgb/1311867266.780320.png 1311867266.789824 depth/1311867266.789824.png
1311867266.812282 rgb/1311867266.812282.png 1311867266.825713 depth/1311867266.825713.png
1311867266.848160 rgb/1311867266.848160.png 1311867266.857500 depth/1311867266.857500.png
1311867266.880318 rgb/1311867266.880318.png 1311867266.889874 depth/1311867266.889874.png
1311867266.912179 rgb/1311867266.912179.png 1311867266.926619 depth/1311867266.926619.png
1311867266.948171 rgb/1311867266.948171.png 1311867266.957655 depth/1311867266.957655.png
1311867266.980363 rgb/1311867266.980363.png 1311867266.992077 depth/1311867266.992077.png
1311867267.012371 rgb/1311867267.012371.png 1311867267.025948 depth/1311867267.025948.png
1311867267.048343 rgb/1311867267.048343.png 1311867267.060361 depth/1311867267.060361.png
1311867267.080246 rgb/1311867267.080246.png 1311867267.092980 depth/1311867267.092980.png
1311867267.112351 rgb/1311867267.112351.png 1311867267.126690 depth/1311867267.126690.png
1311867267.148264 rgb/1311867267.148264.png 1311867267.158691 depth/1311867267.158691.png
1311867267.180231 rgb/1311867267.180231.png 1311867267.191613 depth/1311867267.191613.png
1311867267.212337 rgb/1311867267.212337.png 1311867267.226204 depth/1311867267.226204.png
1311867267.248213 rgb/1311867267.248213.png 1311867267.258745 depth/1311867267.258745.png
1311867267.280459 rgb/1311867267.280459.png 1311867267.292076 depth/1311867267.292076.png
1311867267.312219 rgb/1311867267.312219.png 1311867267.326581 depth/1311867267.326581.png
1311867267.348391 rgb/1311867267.348391.png 1311867267.360995 depth/1311867267.360995.png
1311867267.380442 rgb/1311867267.380442.png 1311867267.394598 depth/1311867267.394598.png
1311867267.412292 rgb/1311867267.412292.png 1311867267.428619 depth/1311867267.428619.png
1311867267.448184 rgb/1311867267.448184.png 1311867267.459579 depth/1311867267.459579.png
1311867267.480293 rgb/1311867267.480293.png 1311867267.493543 depth/1311867267.493543.png
1311867267.512328 rgb/1311867267.512328.png 1311867267.526410 depth/1311867267.526410.png
1311867267.548255 rgb/1311867267.548255.png 1311867267.557797 depth/1311867267.557797.png
1311867267.580291 rgb/1311867267.580291.png 1311867267.595448 depth/1311867267.595448.png
1311867267.612361 rgb/1311867267.612361.png 1311867267.627202 depth/1311867267.627202.png
1311867267.648438 rgb/1311867267.648438.png 1311867267.660897 depth/1311867267.660897.png
1311867267.680321 rgb/1311867267.680321.png 1311867267.695573 depth/1311867267.695573.png
1311867267.712540 rgb/1311867267.712540.png 1311867267.726455 depth/1311867267.726455.png
1311867267.748385 rgb/1311867267.748385.png 1311867267.762498 depth/1311867267.762498.png
1311867267.780391 rgb/1311867267.780391.png 1311867267.795798 depth/1311867267.795798.png
1311867267.812725 rgb/1311867267.812725.png 1311867267.832397 depth/1311867267.832397.png
1311867267.848368 rgb/1311867267.848368.png 1311867267.860108 depth/1311867267.860108.png
1311867267.912736 rgb/1311867267.912736.png 1311867267.898958 depth/1311867267.898958.png
1311867267.948451 rgb/1311867267.948451.png 1311867267.964301 depth/1311867267.964301.png
1311867267.980316 rgb/1311867267.980316.png 1311867267.994746 depth/1311867267.994746.png
1311867268.012300 rgb/1311867268.012300.png 1311867268.028712 depth/1311867268.028712.png
1311867268.048405 rgb/1311867268.048405.png 1311867268.058833 depth/1311867268.058833.png
1311867268.080313 rgb/1311867268.080313.png 1311867268.094608 depth/1311867268.094608.png
1311867268.112446 rgb/1311867268.112446.png 1311867268.125391 depth/1311867268.125391.png
1311867268.148507 rgb/1311867268.148507.png 1311867268.160666 depth/1311867268.160666.png
1311867268.212453 rgb/1311867268.212453.png 1311867268.198196 depth/1311867268.198196.png
1311867268.248305 rgb/1311867268.248305.png 1311867268.257920 depth/1311867268.257920.png
1311867268.280500 rgb/1311867268.280500.png 1311867268.295155 depth/1311867268.295155.png
1311867268.312510 rgb/1311867268.312510.png 1311867268.327417 depth/1311867268.327417.png
1311867268.348270 rgb/1311867268.348270.png 1311867268.358689 depth/1311867268.358689.png
1311867268.380493 rgb/1311867268.380493.png 1311867268.393480 depth/1311867268.393480.png
1311867268.412369 rgb/1311867268.412369.png 1311867268.426148 depth/1311867268.426148.png
1311867268.448606 rgb/1311867268.448606.png 1311867268.458117 depth/1311867268.458117.png
1311867268.480858 rgb/1311867268.480858.png 1311867268.494354 depth/1311867268.494354.png
1311867268.512523 rgb/1311867268.512523.png 1311867268.528033 depth/1311867268.528033.png
1311867268.548506 rgb/1311867268.548506.png 1311867268.561615 depth/1311867268.561615.png
1311867268.580494 rgb/1311867268.580494.png 1311867268.594934 depth/1311867268.594934.png
1311867268.616531 rgb/1311867268.616531.png 1311867268.629458 depth/1311867268.629458.png
1311867268.648346 rgb/1311867268.648346.png 1311867268.663937 depth/1311867268.663937.png
1311867268.680446 rgb/1311867268.680446.png 1311867268.693781 depth/1311867268.693781.png
1311867268.716434 rgb/1311867268.716434.png 1311867268.728257 depth/1311867268.728257.png
1311867268.748466 rgb/1311867268.748466.png 1311867268.762931 depth/1311867268.762931.png
1311867268.780581 rgb/1311867268.780581.png 1311867268.795122 depth/1311867268.795122.png
1311867268.816596 rgb/1311867268.816596.png 1311867268.826463 depth/1311867268.826463.png
1311867268.848629 rgb/1311867268.848629.png 1311867268.861582 depth/1311867268.861582.png
1311867268.880642 rgb/1311867268.880642.png 1311867268.894771 depth/1311867268.894771.png
1311867268.916457 rgb/1311867268.916457.png 1311867268.927190 depth/1311867268.927190.png
1311867268.948366 rgb/1311867268.948366.png 1311867268.963374 depth/1311867268.963374.png
1311867268.980529 rgb/1311867268.980529.png 1311867268.994226 depth/1311867268.994226.png
1311867269.016581 rgb/1311867269.016581.png 1311867269.029342 depth/1311867269.029342.png
1311867269.048325 rgb/1311867269.048325.png 1311867269.062834 depth/1311867269.062834.png
1311867269.082135 rgb/1311867269.082135.png 1311867269.094213 depth/1311867269.094213.png
1311867269.116536 rgb/1311867269.116536.png 1311867269.126398 depth/1311867269.126398.png
1311867269.148627 rgb/1311867269.148627.png 1311867269.161827 depth/1311867269.161827.png
1311867269.180463 rgb/1311867269.180463.png 1311867269.194162 depth/1311867269.194162.png
1311867269.216287 rgb/1311867269.216287.png 1311867269.226625 depth/1311867269.226625.png
1311867269.248318 rgb/1311867269.248318.png 1311867269.262372 depth/1311867269.262372.png
1311867269.280464 rgb/1311867269.280464.png 1311867269.294820 depth/1311867269.294820.png
1311867269.316373 rgb/1311867269.316373.png 1311867269.326183 depth/1311867269.326183.png
1311867269.348345 rgb/1311867269.348345.png 1311867269.364156 depth/1311867269.364156.png
1311867269.380431 rgb/1311867269.380431.png 1311867269.396774 depth/1311867269.396774.png
1311867269.416552 rgb/1311867269.416552.png 1311867269.427582 depth/1311867269.427582.png
1311867269.448314 rgb/1311867269.448314.png 1311867269.462644 depth/1311867269.462644.png
1311867269.480591 rgb/1311867269.480591.png 1311867269.493828 depth/1311867269.493828.png
1311867269.516521 rgb/1311867269.516521.png 1311867269.527859 depth/1311867269.527859.png
1311867269.548348 rgb/1311867269.548348.png 1311867269.563459 depth/1311867269.563459.png
1311867269.580494 rgb/1311867269.580494.png 1311867269.596239 depth/1311867269.596239.png
1311867269.616429 rgb/1311867269.616429.png 1311867269.630608 depth/1311867269.630608.png
1311867269.648449 rgb/1311867269.648449.png 1311867269.663156 depth/1311867269.663156.png
1311867269.680483 rgb/1311867269.680483.png 1311867269.696460 depth/1311867269.696460.png
1311867269.716488 rgb/1311867269.716488.png 1311867269.728087 depth/1311867269.728087.png
1311867269.748333 rgb/1311867269.748333.png 1311867269.762226 depth/1311867269.762226.png
1311867269.780366 rgb/1311867269.780366.png 1311867269.797409 depth/1311867269.797409.png
1311867269.816455 rgb/1311867269.816455.png 1311867269.829587 depth/1311867269.829587.png
1311867269.880365 rgb/1311867269.880365.png 1311867269.867623 depth/1311867269.867623.png
1311867269.948447 rgb/1311867269.948447.png 1311867269.934472 depth/1311867269.934472.png
1311867269.980791 rgb/1311867269.980791.png 1311867269.998726 depth/1311867269.998726.png
1311867270.016606 rgb/1311867270.016606.png 1311867270.030699 depth/1311867270.030699.png
1311867270.048449 rgb/1311867270.048449.png 1311867270.066095 depth/1311867270.066095.png
1311867270.080609 rgb/1311867270.080609.png 1311867270.094820 depth/1311867270.094820.png
1311867270.116645 rgb/1311867270.116645.png 1311867270.133634 depth/1311867270.133634.png
1311867270.148642 rgb/1311867270.148642.png 1311867270.162409 depth/1311867270.162409.png
1311867270.180528 rgb/1311867270.180528.png 1311867270.194354 depth/1311867270.194354.png
1311867270.216437 rgb/1311867270.216437.png 1311867270.232337 depth/1311867270.232337.png
1311867270.280555 rgb/1311867270.280555.png 1311867270.265575 depth/1311867270.265575.png
1311867270.348361 rgb/1311867270.348361.png 1311867270.334610 depth/1311867270.334610.png
1311867270.380591 rgb/1311867270.380591.png 1311867270.395747 depth/1311867270.395747.png
1311867270.448370 rgb/1311867270.448370.png 1311867270.433436 depth/1311867270.433436.png
1311867270.480611 rgb/1311867270.480611.png 1311867270.495461 depth/1311867270.495461.png
1311867270.516588 rgb/1311867270.516588.png 1311867270.533187 depth/1311867270.533187.png
1311867270.548435 rgb/1311867270.548435.png 1311867270.562988 depth/1311867270.562988.png
1311867270.580811 rgb/1311867270.580811.png 1311867270.594486 depth/1311867270.594486.png
1311867270.616443 rgb/1311867270.616443.png 1311867270.631211 depth/1311867270.631211.png
1311867270.648558 rgb/1311867270.648558.png 1311867270.664444 depth/1311867270.664444.png
1311867270.680625 rgb/1311867270.680625.png 1311867270.695018 depth/1311867270.695018.png
1311867270.716482 rgb/1311867270.716482.png 1311867270.731845 depth/1311867270.731845.png
1311867270.748564 rgb/1311867270.748564.png 1311867270.762390 depth/1311867270.762390.png
1311867270.780573 rgb/1311867270.780573.png 1311867270.796050 depth/1311867270.796050.png
1311867270.816524 rgb/1311867270.816524.png 1311867270.832273 depth/1311867270.832273.png
1311867270.848467 rgb/1311867270.848467.png 1311867270.863549 depth/1311867270.863549.png
1311867270.880574 rgb/1311867270.880574.png 1311867270.894589 depth/1311867270.894589.png
1311867270.916494 rgb/1311867270.916494.png 1311867270.932618 depth/1311867270.932618.png
1311867270.948425 rgb/1311867270.948425.png 1311867270.962455 depth/1311867270.962455.png
1311867270.980570 rgb/1311867270.980570.png 1311867270.994456 depth/1311867270.994456.png
1311867271.016615 rgb/1311867271.016615.png 1311867271.030665 depth/1311867271.030665.png
1311867271.048583 rgb/1311867271.048583.png 1311867271.062391 depth/1311867271.062391.png
1311867271.080591 rgb/1311867271.080591.png 1311867271.098346 depth/1311867271.098346.png
1311867271.116562 rgb/1311867271.116562.png 1311867271.132202 depth/1311867271.132202.png
1311867271.152897 rgb/1311867271.152897.png 1311867271.164374 depth/1311867271.164374.png
1311867271.180582 rgb/1311867271.180582.png 1311867271.198803 depth/1311867271.198803.png
1311867271.216570 rgb/1311867271.216570.png 1311867271.232082 depth/1311867271.232082.png
1311867271.280629 rgb/1311867271.280629.png 1311867271.264574 depth/1311867271.264574.png
1311867271.316655 rgb/1311867271.316655.png 1311867271.299855 depth/1311867271.299855.png
1311867271.348780 rgb/1311867271.348780.png 1311867271.335429 depth/1311867271.335429.png
1311867271.380667 rgb/1311867271.380667.png 1311867271.367367 depth/1311867271.367367.png
1311867271.416663 rgb/1311867271.416663.png 1311867271.398881 depth/1311867271.398881.png
1311867271.448701 rgb/1311867271.448701.png 1311867271.435534 depth/1311867271.435534.png
1311867271.480623 rgb/1311867271.480623.png 1311867271.465717 depth/1311867271.465717.png
1311867271.516531 rgb/1311867271.516531.png 1311867271.532396 depth/1311867271.532396.png
1311867271.580572 rgb/1311867271.580572.png 1311867271.567619 depth/1311867271.567619.png
1311867271.616650 rgb/1311867271.616650.png 1311867271.599123 depth/1311867271.599123.png
1311867271.648669 rgb/1311867271.648669.png 1311867271.634989 depth/1311867271.634989.png
1311867271.680718 rgb/1311867271.680718.png 1311867271.665832 depth/1311867271.665832.png
1311867271.716588 rgb/1311867271.716588.png 1311867271.700523 depth/1311867271.700523.png
1311867271.749245 rgb/1311867271.749245.png 1311867271.734954 depth/1311867271.734954.png
1311867271.780613 rgb/1311867271.780613.png 1311867271.766185 depth/1311867271.766185.png
1311867271.816503 rgb/1311867271.816503.png 1311867271.799453 depth/1311867271.799453.png
1311867271.848511 rgb/1311867271.848511.png 1311867271.862915 depth/1311867271.862915.png
1311867271.916677 rgb/1311867271.916677.png 1311867271.930480 depth/1311867271.930480.png
1311867271.980726 rgb/1311867271.980726.png 1311867271.966977 depth/1311867271.966977.png
1311867272.016678 rgb/1311867272.016678.png 1311867272.033760 depth/1311867272.033760.png
1311867272.048486 rgb/1311867272.048486.png 1311867272.062640 depth/1311867272.062640.png
1311867272.116570 rgb/1311867272.116570.png 1311867272.098803 depth/1311867272.098803.png
1311867272.148719 rgb/1311867272.148719.png 1311867272.133621 depth/1311867272.133621.png
1311867272.180820 rgb/1311867272.180820.png 1311867272.165935 depth/1311867272.165935.png
1311867272.216614 rgb/1311867272.216614.png 1311867272.231976 depth/1311867272.231976.png
1311867272.280675 rgb/1311867272.280675.png 1311867272.265511 depth/1311867272.265511.png
1311867272.316580 rgb/1311867272.316580.png 1311867272.331502 depth/1311867272.331502.png
1311867272.380604 rgb/1311867272.380604.png 1311867272.369675 depth/1311867272.369675.png
1311867272.416575 rgb/1311867272.416575.png 1311867272.398705 depth/1311867272.398705.png
1311867272.448579 rgb/1311867272.448579.png 1311867272.433573 depth/1311867272.433573.png
1311867272.481087 rgb/1311867272.481087.png 1311867272.468614 depth/1311867272.468614.png
1311867272.516777 rgb/1311867272.516777.png 1311867272.501142 depth/1311867272.501142.png
1311867272.548588 rgb/1311867272.548588.png 1311867272.532548 depth/1311867272.532548.png
1311867272.580582 rgb/1311867272.580582.png 1311867272.567660 depth/1311867272.567660.png
1311867272.616652 rgb/1311867272.616652.png 1311867272.631536 depth/1311867272.631536.png
1311867272.680692 rgb/1311867272.680692.png 1311867272.666129 depth/1311867272.666129.png
1311867272.716489 rgb/1311867272.716489.png 1311867272.730711 depth/1311867272.730711.png
1311867272.780656 rgb/1311867272.780656.png 1311867272.768615 depth/1311867272.768615.png
1311867272.816623 rgb/1311867272.816623.png 1311867272.831016 depth/1311867272.831016.png
1311867272.880537 rgb/1311867272.880537.png 1311867272.867485 depth/1311867272.867485.png
1311867272.916603 rgb/1311867272.916603.png 1311867272.931411 depth/1311867272.931411.png
1311867272.980676 rgb/1311867272.980676.png 1311867272.966467 depth/1311867272.966467.png
1311867273.016608 rgb/1311867273.016608.png 1311867272.998760 depth/1311867272.998760.png
1311867273.048578 rgb/1311867273.048578.png 1311867273.032849 depth/1311867273.032849.png
1311867273.080754 rgb/1311867273.080754.png 1311867273.066274 depth/1311867273.066274.png
1311867273.116731 rgb/1311867273.116731.png 1311867273.131071 depth/1311867273.131071.png
1311867273.180697 rgb/1311867273.180697.png 1311867273.166574 depth/1311867273.166574.png
1311867273.216838 rgb/1311867273.216838.png 1311867273.199752 depth/1311867273.199752.png
1311867273.248544 rgb/1311867273.248544.png 1311867273.233182 depth/1311867273.233182.png
1311867273.280714 rgb/1311867273.280714.png 1311867273.266838 depth/1311867273.266838.png
1311867273.316838 rgb/1311867273.316838.png 1311867273.330801 depth/1311867273.330801.png
1311867273.380697 rgb/1311867273.380697.png 1311867273.366351 depth/1311867273.366351.png
1311867273.416830 rgb/1311867273.416830.png 1311867273.430841 depth/1311867273.430841.png
1311867273.480769 rgb/1311867273.480769.png 1311867273.466325 depth/1311867273.466325.png
1311867273.516690 rgb/1311867273.516690.png 1311867273.531842 depth/1311867273.531842.png
1311867273.580631 rgb/1311867273.580631.png 1311867273.568791 depth/1311867273.568791.png
1311867273.616742 rgb/1311867273.616742.png 1311867273.600039 depth/1311867273.600039.png
1311867273.648674 rgb/1311867273.648674.png 1311867273.634960 depth/1311867273.634960.png
1311867273.680974 rgb/1311867273.680974.png 1311867273.667377 depth/1311867273.667377.png
1311867273.716707 rgb/1311867273.716707.png 1311867273.698786 depth/1311867273.698786.png
1311867273.748711 rgb/1311867273.748711.png 1311867273.734674 depth/1311867273.734674.png
1311867273.780735 rgb/1311867273.780735.png 1311867273.766596 depth/1311867273.766596.png
1311867273.816639 rgb/1311867273.816639.png 1311867273.799070 depth/1311867273.799070.png
1311867273.849123 rgb/1311867273.849123.png 1311867273.835813 depth/1311867273.835813.png
1311867273.880737 rgb/1311867273.880737.png 1311867273.866806 depth/1311867273.866806.png
1311867273.916618 rgb/1311867273.916618.png 1311867273.899072 depth/1311867273.899072.png
1311867273.949213 rgb/1311867273.949213.png 1311867273.938482 depth/1311867273.938482.png
1311867273.980666 rgb/1311867273.980666.png 1311867273.966905 depth/1311867273.966905.png
1311867274.016822 rgb/1311867274.016822.png 1311867273.999658 depth/1311867273.999658.png
1311867274.048756 rgb/1311867274.048756.png 1311867274.034849 depth/1311867274.034849.png
1311867274.080678 rgb/1311867274.080678.png 1311867274.067002 depth/1311867274.067002.png
1311867274.116619 rgb/1311867274.116619.png 1311867274.102568 depth/1311867274.102568.png
1311867274.149224 rgb/1311867274.149224.png 1311867274.135057 depth/1311867274.135057.png
1311867274.180919 rgb/1311867274.180919.png 1311867274.166797 depth/1311867274.166797.png
1311867274.216954 rgb/1311867274.216954.png 1311867274.200855 depth/1311867274.200855.png
1311867274.248965 rgb/1311867274.248965.png 1311867274.238918 depth/1311867274.238918.png
1311867274.280784 rgb/1311867274.280784.png 1311867274.266854 depth/1311867274.266854.png
1311867274.317121 rgb/1311867274.317121.png 1311867274.301894 depth/1311867274.301894.png
1311867274.348830 rgb/1311867274.348830.png 1311867274.335814 depth/1311867274.335814.png
1311867274.380862 rgb/1311867274.380862.png 1311867274.367976 depth/1311867274.367976.png
1311867274.416837 rgb/1311867274.416837.png 1311867274.400755 depth/1311867274.400755.png
1311867274.448780 rgb/1311867274.448780.png 1311867274.435768 depth/1311867274.435768.png
1311867274.480661 rgb/1311867274.480661.png 1311867274.468921 depth/1311867274.468921.png
1311867274.516798 rgb/1311867274.516798.png 1311867274.499770 depth/1311867274.499770.png
1311867274.548944 rgb/1311867274.548944.png 1311867274.534598 depth/1311867274.534598.png
1311867274.580883 rgb/1311867274.580883.png 1311867274.568684 depth/1311867274.568684.png
1311867274.616863 rgb/1311867274.616863.png 1311867274.600119 depth/1311867274.600119.png
1311867274.649010 rgb/1311867274.649010.png 1311867274.634927 depth/1311867274.634927.png
1311867274.680804 rgb/1311867274.680804.png 1311867274.666565 depth/1311867274.666565.png
1311867274.716711 rgb/1311867274.716711.png 1311867274.698870 depth/1311867274.698870.png
1311867274.748763 rgb/1311867274.748763.png 1311867274.735576 depth/1311867274.735576.png
1311867274.780646 rgb/1311867274.780646.png 1311867274.766900 depth/1311867274.766900.png
1311867274.816702 rgb/1311867274.816702.png 1311867274.804002 depth/1311867274.804002.png
1311867274.848794 rgb/1311867274.848794.png 1311867274.835089 depth/1311867274.835089.png
1311867274.880821 rgb/1311867274.880821.png 1311867274.867136 depth/1311867274.867136.png
1311867274.916628 rgb/1311867274.916628.png 1311867274.904429 depth/1311867274.904429.png
1311867274.948646 rgb/1311867274.948646.png 1311867274.935055 depth/1311867274.935055.png
1311867274.980903 rgb/1311867274.980903.png 1311867274.966649 depth/1311867274.966649.png
1311867275.016675 rgb/1311867275.016675.png 1311867275.003083 depth/1311867275.003083.png
1311867275.048721 rgb/1311867275.048721.png 1311867275.036808 depth/1311867275.036808.png
1311867275.080754 rgb/1311867275.080754.png 1311867275.066445 depth/1311867275.066445.png
1311867275.116833 rgb/1311867275.116833.png 1311867275.102327 depth/1311867275.102327.png
1311867275.148689 rgb/1311867275.148689.png 1311867275.135123 depth/1311867275.135123.png
1311867275.180701 rgb/1311867275.180701.png 1311867275.166718 depth/1311867275.166718.png
1311867275.216737 rgb/1311867275.216737.png 1311867275.204175 depth/1311867275.204175.png
1311867275.248735 rgb/1311867275.248735.png 1311867275.237178 depth/1311867275.237178.png
1311867275.280811 rgb/1311867275.280811.png 1311867275.266818 depth/1311867275.266818.png
1311867275.316666 rgb/1311867275.316666.png 1311867275.302680 depth/1311867275.302680.png
1311867275.348709 rgb/1311867275.348709.png 1311867275.335188 depth/1311867275.335188.png
1311867275.381040 rgb/1311867275.381040.png 1311867275.366911 depth/1311867275.366911.png
1311867275.416695 rgb/1311867275.416695.png 1311867275.403837 depth/1311867275.403837.png
1311867275.448851 rgb/1311867275.448851.png 1311867275.434960 depth/1311867275.434960.png
1311867275.480860 rgb/1311867275.480860.png 1311867275.466940 depth/1311867275.466940.png
1311867275.516817 rgb/1311867275.516817.png 1311867275.503729 depth/1311867275.503729.png
1311867275.548814 rgb/1311867275.548814.png 1311867275.535333 depth/1311867275.535333.png
1311867275.580874 rgb/1311867275.580874.png 1311867275.566891 depth/1311867275.566891.png
1311867275.616794 rgb/1311867275.616794.png 1311867275.602830 depth/1311867275.602830.png
1311867275.648733 rgb/1311867275.648733.png 1311867275.638328 depth/1311867275.638328.png
1311867275.680883 rgb/1311867275.680883.png 1311867275.668221 depth/1311867275.668221.png
1311867275.716827 rgb/1311867275.716827.png 1311867275.704589 depth/1311867275.704589.png
1311867275.749216 rgb/1311867275.749216.png 1311867275.734982 depth/1311867275.734982.png
1311867275.780810 rgb/1311867275.780810.png 1311867275.779228 depth/1311867275.779228.png
1311867275.816772 rgb/1311867275.816772.png 1311867275.802849 depth/1311867275.802849.png
1311867275.848840 rgb/1311867275.848840.png 1311867275.835596 depth/1311867275.835596.png
1311867275.880760 rgb/1311867275.880760.png 1311867275.870156 depth/1311867275.870156.png
1311867275.917061 rgb/1311867275.917061.png 1311867275.903212 depth/1311867275.903212.png
1311867275.948821 rgb/1311867275.948821.png 1311867275.937132 depth/1311867275.937132.png
1311867275.980896 rgb/1311867275.980896.png 1311867275.968386 depth/1311867275.968386.png
1311867276.016817 rgb/1311867276.016817.png 1311867276.004847 depth/1311867276.004847.png
1311867276.048985 rgb/1311867276.048985.png 1311867276.038754 depth/1311867276.038754.png
1311867276.081061 rgb/1311867276.081061.png 1311867276.073903 depth/1311867276.073903.png
1311867276.117046 rgb/1311867276.117046.png 1311867276.105137 depth/1311867276.105137.png
1311867276.148911 rgb/1311867276.148911.png 1311867276.138238 depth/1311867276.138238.png
1311867276.180826 rgb/1311867276.180826.png 1311867276.170939 depth/1311867276.170939.png
1311867276.216827 rgb/1311867276.216827.png 1311867276.204228 depth/1311867276.204228.png
1311867276.248954 rgb/1311867276.248954.png 1311867276.235786 depth/1311867276.235786.png
1311867276.281034 rgb/1311867276.281034.png 1311867276.274772 depth/1311867276.274772.png
1311867276.316847 rgb/1311867276.316847.png 1311867276.302752 depth/1311867276.302752.png
1311867276.348823 rgb/1311867276.348823.png 1311867276.338719 depth/1311867276.338719.png
1311867276.380997 rgb/1311867276.380997.png 1311867276.372960 depth/1311867276.372960.png
1311867276.416760 rgb/1311867276.416760.png 1311867276.403193 depth/1311867276.403193.png
1311867276.449013 rgb/1311867276.449013.png 1311867276.436013 depth/1311867276.436013.png
1311867276.481045 rgb/1311867276.481045.png 1311867276.473709 depth/1311867276.473709.png
1311867276.516812 rgb/1311867276.516812.png 1311867276.504842 depth/1311867276.504842.png
1311867276.548975 rgb/1311867276.548975.png 1311867276.538747 depth/1311867276.538747.png
1311867276.581007 rgb/1311867276.581007.png 1311867276.574678 depth/1311867276.574678.png
1311867276.616955 rgb/1311867276.616955.png 1311867276.604192 depth/1311867276.604192.png
1311867276.648797 rgb/1311867276.648797.png 1311867276.636147 depth/1311867276.636147.png
1311867276.680881 rgb/1311867276.680881.png 1311867276.671092 depth/1311867276.671092.png
1311867276.716834 rgb/1311867276.716834.png 1311867276.702972 depth/1311867276.702972.png
1311867276.749007 rgb/1311867276.749007.png 1311867276.736078 depth/1311867276.736078.png
1311867276.781174 rgb/1311867276.781174.png 1311867276.772196 depth/1311867276.772196.png
1311867276.816885 rgb/1311867276.816885.png 1311867276.802909 depth/1311867276.802909.png
1311867276.849154 rgb/1311867276.849154.png 1311867276.837570 depth/1311867276.837570.png
1311867276.880864 rgb/1311867276.880864.png 1311867276.874097 depth/1311867276.874097.png
1311867276.916961 rgb/1311867276.916961.png 1311867276.902975 depth/1311867276.902975.png
1311867276.948866 rgb/1311867276.948866.png 1311867276.937498 depth/1311867276.937498.png
1311867276.980866 rgb/1311867276.980866.png 1311867276.972691 depth/1311867276.972691.png
1311867277.016880 rgb/1311867277.016880.png 1311867277.005003 depth/1311867277.005003.png
1311867277.049009 rgb/1311867277.049009.png 1311867277.035607 depth/1311867277.035607.png
1311867277.081265 rgb/1311867277.081265.png 1311867277.071161 depth/1311867277.071161.png
1311867277.116824 rgb/1311867277.116824.png 1311867277.103977 depth/1311867277.103977.png
1311867277.148834 rgb/1311867277.148834.png 1311867277.135027 depth/1311867277.135027.png
1311867277.180831 rgb/1311867277.180831.png 1311867277.170849 depth/1311867277.170849.png
1311867277.216967 rgb/1311867277.216967.png 1311867277.202976 depth/1311867277.202976.png
1311867277.248926 rgb/1311867277.248926.png 1311867277.235100 depth/1311867277.235100.png
1311867277.280849 rgb/1311867277.280849.png 1311867277.273315 depth/1311867277.273315.png
1311867277.316929 rgb/1311867277.316929.png 1311867277.306378 depth/1311867277.306378.png
1311867277.349051 rgb/1311867277.349051.png 1311867277.339603 depth/1311867277.339603.png
1311867277.384209 rgb/1311867277.384209.png 1311867277.377389 depth/1311867277.377389.png
1311867277.416922 rgb/1311867277.416922.png 1311867277.405553 depth/1311867277.405553.png
1311867277.450161 rgb/1311867277.450161.png 1311867277.442508 depth/1311867277.442508.png
1311867277.480901 rgb/1311867277.480901.png 1311867277.472375 depth/1311867277.472375.png
1311867277.517078 rgb/1311867277.517078.png 1311867277.505778 depth/1311867277.505778.png
1311867277.548828 rgb/1311867277.548828.png 1311867277.540194 depth/1311867277.540194.png
1311867277.580920 rgb/1311867277.580920.png 1311867277.571535 depth/1311867277.571535.png
1311867277.616897 rgb/1311867277.616897.png 1311867277.602771 depth/1311867277.602771.png
1311867277.649076 rgb/1311867277.649076.png 1311867277.641613 depth/1311867277.641613.png
1311867277.681057 rgb/1311867277.681057.png 1311867277.671301 depth/1311867277.671301.png
1311867277.717139 rgb/1311867277.717139.png 1311867277.706359 depth/1311867277.706359.png
1311867277.748909 rgb/1311867277.748909.png 1311867277.740141 depth/1311867277.740141.png
1311867277.784818 rgb/1311867277.784818.png 1311867277.772008 depth/1311867277.772008.png
1311867277.816868 rgb/1311867277.816868.png 1311867277.803688 depth/1311867277.803688.png
1311867277.848906 rgb/1311867277.848906.png 1311867277.840050 depth/1311867277.840050.png
1311867277.884896 rgb/1311867277.884896.png 1311867277.871117 depth/1311867277.871117.png
1311867277.916858 rgb/1311867277.916858.png 1311867277.903161 depth/1311867277.903161.png
1311867277.948933 rgb/1311867277.948933.png 1311867277.939302 depth/1311867277.939302.png
1311867277.985092 rgb/1311867277.985092.png 1311867277.971423 depth/1311867277.971423.png
1311867278.016848 rgb/1311867278.016848.png 1311867278.004136 depth/1311867278.004136.png
1311867278.049001 rgb/1311867278.049001.png 1311867278.039421 depth/1311867278.039421.png
1311867278.084826 rgb/1311867278.084826.png 1311867278.071263 depth/1311867278.071263.png
1311867278.116862 rgb/1311867278.116862.png 1311867278.105629 depth/1311867278.105629.png
1311867278.149018 rgb/1311867278.149018.png 1311867278.139198 depth/1311867278.139198.png
1311867278.184865 rgb/1311867278.184865.png 1311867278.171037 depth/1311867278.171037.png
1311867278.216940 rgb/1311867278.216940.png 1311867278.203861 depth/1311867278.203861.png
1311867278.248940 rgb/1311867278.248940.png 1311867278.238806 depth/1311867278.238806.png
1311867278.284908 rgb/1311867278.284908.png 1311867278.270763 depth/1311867278.270763.png
1311867278.317404 rgb/1311867278.317404.png 1311867278.302763 depth/1311867278.302763.png
1311867278.349011 rgb/1311867278.349011.png 1311867278.342160 depth/1311867278.342160.png
1311867278.384931 rgb/1311867278.384931.png 1311867278.371436 depth/1311867278.371436.png
1311867278.416856 rgb/1311867278.416856.png 1311867278.403535 depth/1311867278.403535.png
1311867278.448914 rgb/1311867278.448914.png 1311867278.439117 depth/1311867278.439117.png
1311867278.485032 rgb/1311867278.485032.png 1311867278.471334 depth/1311867278.471334.png
1311867278.516899 rgb/1311867278.516899.png 1311867278.504124 depth/1311867278.504124.png
1311867278.549265 rgb/1311867278.549265.png 1311867278.542391 depth/1311867278.542391.png
1311867278.584923 rgb/1311867278.584923.png 1311867278.571026 depth/1311867278.571026.png
1311867278.616874 rgb/1311867278.616874.png 1311867278.606903 depth/1311867278.606903.png
1311867278.649080 rgb/1311867278.649080.png 1311867278.639324 depth/1311867278.639324.png
1311867278.684905 rgb/1311867278.684905.png 1311867278.670971 depth/1311867278.670971.png
1311867278.717052 rgb/1311867278.717052.png 1311867278.706913 depth/1311867278.706913.png
1311867278.749117 rgb/1311867278.749117.png 1311867278.739068 depth/1311867278.739068.png
1311867278.785013 rgb/1311867278.785013.png 1311867278.771830 depth/1311867278.771830.png
1311867278.816933 rgb/1311867278.816933.png 1311867278.806824 depth/1311867278.806824.png
1311867278.848909 rgb/1311867278.848909.png 1311867278.838653 depth/1311867278.838653.png
1311867278.884953 rgb/1311867278.884953.png 1311867278.874170 depth/1311867278.874170.png
1311867278.916959 rgb/1311867278.916959.png 1311867278.909065 depth/1311867278.909065.png
1311867278.949082 rgb/1311867278.949082.png 1311867278.939277 depth/1311867278.939277.png
1311867278.985050 rgb/1311867278.985050.png 1311867278.971143 depth/1311867278.971143.png
1311867279.016951 rgb/1311867279.016951.png 1311867279.007311 depth/1311867279.007311.png
1311867279.049207 rgb/1311867279.049207.png 1311867279.039773 depth/1311867279.039773.png
1311867279.085000 rgb/1311867279.085000.png 1311867279.073854 depth/1311867279.073854.png
1311867279.117024 rgb/1311867279.117024.png 1311867279.106844 depth/1311867279.106844.png
1311867279.149152 rgb/1311867279.149152.png 1311867279.139249 depth/1311867279.139249.png
1311867279.185056 rgb/1311867279.185056.png 1311867279.171204 depth/1311867279.171204.png
1311867279.216910 rgb/1311867279.216910.png 1311867279.207044 depth/1311867279.207044.png
1311867279.249252 rgb/1311867279.249252.png 1311867279.241121 depth/1311867279.241121.png
1311867279.284982 rgb/1311867279.284982.png 1311867279.271776 depth/1311867279.271776.png
1311867279.317001 rgb/1311867279.317001.png 1311867279.306722 depth/1311867279.306722.png
1311867279.349109 rgb/1311867279.349109.png 1311867279.338809 depth/1311867279.338809.png
1311867279.385350 rgb/1311867279.385350.png 1311867279.380493 depth/1311867279.380493.png
1311867279.417132 rgb/1311867279.417132.png 1311867279.408991 depth/1311867279.408991.png
1311867279.448972 rgb/1311867279.448972.png 1311867279.441097 depth/1311867279.441097.png
1311867279.485178 rgb/1311867279.485178.png 1311867279.472557 depth/1311867279.472557.png
1311867279.517352 rgb/1311867279.517352.png 1311867279.509571 depth/1311867279.509571.png
1311867279.549112 rgb/1311867279.549112.png 1311867279.540739 depth/1311867279.540739.png
1311867279.585000 rgb/1311867279.585000.png 1311867279.573423 depth/1311867279.573423.png
1311867279.617658 rgb/1311867279.617658.png 1311867279.612164 depth/1311867279.612164.png
1311867279.649149 rgb/1311867279.649149.png 1311867279.638944 depth/1311867279.638944.png
1311867279.685122 rgb/1311867279.685122.png 1311867279.674977 depth/1311867279.674977.png
1311867279.717608 rgb/1311867279.717608.png 1311867279.710798 depth/1311867279.710798.png
1311867279.749168 rgb/1311867279.749168.png 1311867279.741020 depth/1311867279.741020.png
1311867279.785184 rgb/1311867279.785184.png 1311867279.777706 depth/1311867279.777706.png
1311867279.817277 rgb/1311867279.817277.png 1311867279.811885 depth/1311867279.811885.png
1311867279.849225 rgb/1311867279.849225.png 1311867279.843825 depth/1311867279.843825.png
1311867279.885430 rgb/1311867279.885430.png 1311867279.880883 depth/1311867279.880883.png
1311867279.917304 rgb/1311867279.917304.png 1311867279.908818 depth/1311867279.908818.png
1311867279.952401 rgb/1311867279.952401.png 1311867279.944041 depth/1311867279.944041.png
1311867279.985229 rgb/1311867279.985229.png 1311867279.979519 depth/1311867279.979519.png
1311867280.018481 rgb/1311867280.018481.png 1311867280.011379 depth/1311867280.011379.png
1311867280.049281 rgb/1311867280.049281.png 1311867280.040186 depth/1311867280.040186.png
1311867280.085300 rgb/1311867280.085300.png 1311867280.078508 depth/1311867280.078508.png
1311867280.117762 rgb/1311867280.117762.png 1311867280.111193 depth/1311867280.111193.png
1311867280.149143 rgb/1311867280.149143.png 1311867280.145007 depth/1311867280.145007.png
1311867280.185202 rgb/1311867280.185202.png 1311867280.175310 depth/1311867280.175310.png
1311867280.218467 rgb/1311867280.218467.png 1311867280.212334 depth/1311867280.212334.png
1311867280.249139 rgb/1311867280.249139.png 1311867280.242286 depth/1311867280.242286.png
1311867280.285235 rgb/1311867280.285235.png 1311867280.279458 depth/1311867280.279458.png
1311867280.317120 rgb/1311867280.317120.png 1311867280.311473 depth/1311867280.311473.png
1311867280.349364 rgb/1311867280.349364.png 1311867280.344508 depth/1311867280.344508.png
1311867280.384986 rgb/1311867280.384986.png 1311867280.375534 depth/1311867280.375534.png
1311867280.417089 rgb/1311867280.417089.png 1311867280.407190 depth/1311867280.407190.png
1311867280.449359 rgb/1311867280.449359.png 1311867280.442411 depth/1311867280.442411.png
1311867280.485243 rgb/1311867280.485243.png 1311867280.478287 depth/1311867280.478287.png
1311867280.517164 rgb/1311867280.517164.png 1311867280.509126 depth/1311867280.509126.png
1311867280.549209 rgb/1311867280.549209.png 1311867280.545599 depth/1311867280.545599.png
1311867280.585098 rgb/1311867280.585098.png 1311867280.578208 depth/1311867280.578208.png
1311867280.619113 rgb/1311867280.619113.png 1311867280.613050 depth/1311867280.613050.png
1311867280.649186 rgb/1311867280.649186.png 1311867280.642274 depth/1311867280.642274.png
1311867280.685076 rgb/1311867280.685076.png 1311867280.675529 depth/1311867280.675529.png
1311867280.717291 rgb/1311867280.717291.png 1311867280.709488 depth/1311867280.709488.png
1311867280.749156 rgb/1311867280.749156.png 1311867280.741181 depth/1311867280.741181.png
1311867280.785051 rgb/1311867280.785051.png 1311867280.775267 depth/1311867280.775267.png
1311867280.817244 rgb/1311867280.817244.png 1311867280.807625 depth/1311867280.807625.png
1311867280.849336 rgb/1311867280.849336.png 1311867280.840101 depth/1311867280.840101.png
1311867280.885032 rgb/1311867280.885032.png 1311867280.875484 depth/1311867280.875484.png
1311867280.917146 rgb/1311867280.917146.png 1311867280.907911 depth/1311867280.907911.png
1311867280.949429 rgb/1311867280.949429.png 1311867280.939453 depth/1311867280.939453.png
1311867280.985057 rgb/1311867280.985057.png 1311867280.976699 depth/1311867280.976699.png
1311867281.017255 rgb/1311867281.017255.png 1311867281.007519 depth/1311867281.007519.png
1311867281.049159 rgb/1311867281.049159.png 1311867281.043343 depth/1311867281.043343.png
1311867281.085147 rgb/1311867281.085147.png 1311867281.075278 depth/1311867281.075278.png
1311867281.117112 rgb/1311867281.117112.png 1311867281.107490 depth/1311867281.107490.png
1311867281.149430 rgb/1311867281.149430.png 1311867281.145152 depth/1311867281.145152.png
1311867281.185052 rgb/1311867281.185052.png 1311867281.178669 depth/1311867281.178669.png
1311867281.217252 rgb/1311867281.217252.png 1311867281.208330 depth/1311867281.208330.png
1311867281.250106 rgb/1311867281.250106.png 1311867281.245795 depth/1311867281.245795.png
1311867281.285102 rgb/1311867281.285102.png 1311867281.275440 depth/1311867281.275440.png
1311867281.317215 rgb/1311867281.317215.png 1311867281.307299 depth/1311867281.307299.png
1311867281.349217 rgb/1311867281.349217.png 1311867281.346510 depth/1311867281.346510.png
1311867281.385101 rgb/1311867281.385101.png 1311867281.375153 depth/1311867281.375153.png
1311867281.417074 rgb/1311867281.417074.png 1311867281.408070 depth/1311867281.408070.png
1311867281.449183 rgb/1311867281.449183.png 1311867281.443411 depth/1311867281.443411.png
1311867281.485107 rgb/1311867281.485107.png 1311867281.475372 depth/1311867281.475372.png
1311867281.517167 rgb/1311867281.517167.png 1311867281.510197 depth/1311867281.510197.png
1311867281.549207 rgb/1311867281.549207.png 1311867281.543566 depth/1311867281.543566.png
1311867281.585193 rgb/1311867281.585193.png 1311867281.575475 depth/1311867281.575475.png
1311867281.617286 rgb/1311867281.617286.png 1311867281.611119 depth/1311867281.611119.png
1311867281.649274 rgb/1311867281.649274.png 1311867281.643561 depth/1311867281.643561.png
1311867281.685142 rgb/1311867281.685142.png 1311867281.675512 depth/1311867281.675512.png
1311867281.717170 rgb/1311867281.717170.png 1311867281.708919 depth/1311867281.708919.png
1311867281.749309 rgb/1311867281.749309.png 1311867281.745224 depth/1311867281.745224.png
1311867281.785115 rgb/1311867281.785115.png 1311867281.775529 depth/1311867281.775529.png
1311867281.817105 rgb/1311867281.817105.png 1311867281.807558 depth/1311867281.807558.png
1311867281.849170 rgb/1311867281.849170.png 1311867281.844782 depth/1311867281.844782.png
1311867281.885079 rgb/1311867281.885079.png 1311867281.875666 depth/1311867281.875666.png
1311867281.917153 rgb/1311867281.917153.png 1311867281.907723 depth/1311867281.907723.png
1311867281.949198 rgb/1311867281.949198.png 1311867281.944487 depth/1311867281.944487.png
1311867281.985074 rgb/1311867281.985074.png 1311867281.978540 depth/1311867281.978540.png
1311867282.017320 rgb/1311867282.017320.png 1311867282.009812 depth/1311867282.009812.png
1311867282.049154 rgb/1311867282.049154.png 1311867282.043680 depth/1311867282.043680.png
1311867282.085212 rgb/1311867282.085212.png 1311867282.075547 depth/1311867282.075547.png
1311867282.117596 rgb/1311867282.117596.png 1311867282.107791 depth/1311867282.107791.png
1311867282.154864 rgb/1311867282.154864.png 1311867282.146414 depth/1311867282.146414.png
1311867282.188493 rgb/1311867282.188493.png 1311867282.179748 depth/1311867282.179748.png
1311867282.219908 rgb/1311867282.219908.png 1311867282.213633 depth/1311867282.213633.png
1311867282.253156 rgb/1311867282.253156.png 1311867282.245317 depth/1311867282.245317.png
1311867282.288070 rgb/1311867282.288070.png 1311867282.284410 depth/1311867282.284410.png
1311867282.322429 rgb/1311867282.322429.png 1311867282.318730 depth/1311867282.318730.png
1311867282.350083 rgb/1311867282.350083.png 1311867282.344555 depth/1311867282.344555.png
1311867282.390746 rgb/1311867282.390746.png 1311867282.383713 depth/1311867282.383713.png
1311867282.417372 rgb/1311867282.417372.png 1311867282.411485 depth/1311867282.411485.png
1311867282.449215 rgb/1311867282.449215.png 1311867282.443704 depth/1311867282.443704.png
1311867282.485251 rgb/1311867282.485251.png 1311867282.475457 depth/1311867282.475457.png
1311867282.517375 rgb/1311867282.517375.png 1311867282.512856 depth/1311867282.512856.png
1311867282.549242 rgb/1311867282.549242.png 1311867282.543540 depth/1311867282.543540.png
1311867282.585190 rgb/1311867282.585190.png 1311867282.575564 depth/1311867282.575564.png
1311867282.617188 rgb/1311867282.617188.png 1311867282.611290 depth/1311867282.611290.png
1311867282.649230 rgb/1311867282.649230.png 1311867282.643726 depth/1311867282.643726.png
1311867282.685172 rgb/1311867282.685172.png 1311867282.676659 depth/1311867282.676659.png
1311867282.717391 rgb/1311867282.717391.png 1311867282.714725 depth/1311867282.714725.png
1311867282.749855 rgb/1311867282.749855.png 1311867282.746252 depth/1311867282.746252.png
1311867282.785198 rgb/1311867282.785198.png 1311867282.775429 depth/1311867282.775429.png
1311867282.817434 rgb/1311867282.817434.png 1311867282.811635 depth/1311867282.811635.png
1311867282.849193 rgb/1311867282.849193.png 1311867282.847537 depth/1311867282.847537.png
1311867282.885734 rgb/1311867282.885734.png 1311867282.875791 depth/1311867282.875791.png
1311867282.917314 rgb/1311867282.917314.png 1311867282.911463 depth/1311867282.911463.png
1311867282.950235 rgb/1311867282.950235.png 1311867282.945648 depth/1311867282.945648.png
1311867282.985476 rgb/1311867282.985476.png 1311867282.981189 depth/1311867282.981189.png
1311867283.017555 rgb/1311867283.017555.png 1311867283.011488 depth/1311867283.011488.png
1311867283.049392 rgb/1311867283.049392.png 1311867283.046246 depth/1311867283.046246.png
1311867283.085258 rgb/1311867283.085258.png 1311867283.075293 depth/1311867283.075293.png
1311867283.117441 rgb/1311867283.117441.png 1311867283.111688 depth/1311867283.111688.png
1311867283.149532 rgb/1311867283.149532.png 1311867283.143551 depth/1311867283.143551.png
1311867283.185409 rgb/1311867283.185409.png 1311867283.178822 depth/1311867283.178822.png
1311867283.217286 rgb/1311867283.217286.png 1311867283.215827 depth/1311867283.215827.png
1311867283.249357 rgb/1311867283.249357.png 1311867283.244175 depth/1311867283.244175.png
1311867283.285375 rgb/1311867283.285375.png 1311867283.277684 depth/1311867283.277684.png
1311867283.317623 rgb/1311867283.317623.png 1311867283.313466 depth/1311867283.313466.png
1311867283.349796 rgb/1311867283.349796.png 1311867283.349803 depth/1311867283.349803.png
1311867283.385222 rgb/1311867283.385222.png 1311867283.378247 depth/1311867283.378247.png
1311867283.417308 rgb/1311867283.417308.png 1311867283.411527 depth/1311867283.411527.png
1311867283.449265 rgb/1311867283.449265.png 1311867283.446462 depth/1311867283.446462.png
1311867283.485337 rgb/1311867283.485337.png 1311867283.483432 depth/1311867283.483432.png
1311867283.517216 rgb/1311867283.517216.png 1311867283.515474 depth/1311867283.515474.png
1311867283.549561 rgb/1311867283.549561.png 1311867283.543357 depth/1311867283.543357.png
1311867283.585388 rgb/1311867283.585388.png 1311867283.580230 depth/1311867283.580230.png
1311867283.617318 rgb/1311867283.617318.png 1311867283.611350 depth/1311867283.611350.png
1311867283.649382 rgb/1311867283.649382.png 1311867283.643515 depth/1311867283.643515.png
1311867283.685288 rgb/1311867283.685288.png 1311867283.682435 depth/1311867283.682435.png
1311867283.717915 rgb/1311867283.717915.png 1311867283.712030 depth/1311867283.712030.png
1311867283.749208 rgb/1311867283.749208.png 1311867283.747805 depth/1311867283.747805.png
1311867283.785317 rgb/1311867283.785317.png 1311867283.781469 depth/1311867283.781469.png
1311867283.817413 rgb/1311867283.817413.png 1311867283.811886 depth/1311867283.811886.png
1311867283.849452 rgb/1311867283.849452.png 1311867283.844653 depth/1311867283.844653.png
1311867283.885346 rgb/1311867283.885346.png 1311867283.882707 depth/1311867283.882707.png
1311867283.917540 rgb/1311867283.917540.png 1311867283.916866 depth/1311867283.916866.png
1311867283.949890 rgb/1311867283.949890.png 1311867283.945388 depth/1311867283.945388.png
1311867283.985663 rgb/1311867283.985663.png 1311867283.983650 depth/1311867283.983650.png
1311867284.017300 rgb/1311867284.017300.png 1311867284.015752 depth/1311867284.015752.png
1311867284.049779 rgb/1311867284.049779.png 1311867284.043327 depth/1311867284.043327.png
1311867284.085373 rgb/1311867284.085373.png 1311867284.082619 depth/1311867284.082619.png
1311867284.117504 rgb/1311867284.117504.png 1311867284.111840 depth/1311867284.111840.png
1311867284.149411 rgb/1311867284.149411.png 1311867284.145447 depth/1311867284.145447.png
1311867284.187489 rgb/1311867284.187489.png 1311867284.182905 depth/1311867284.182905.png
1311867284.217337 rgb/1311867284.217337.png 1311867284.213992 depth/1311867284.213992.png
1311867284.249431 rgb/1311867284.249431.png 1311867284.245100 depth/1311867284.245100.png
1311867284.285316 rgb/1311867284.285316.png 1311867284.282897 depth/1311867284.282897.png
1311867284.317835 rgb/1311867284.317835.png 1311867284.312841 depth/1311867284.312841.png
1311867284.349424 rgb/1311867284.349424.png 1311867284.343838 depth/1311867284.343838.png
1311867284.385433 rgb/1311867284.385433.png 1311867284.379601 depth/1311867284.379601.png
1311867284.417580 rgb/1311867284.417580.png 1311867284.416106 depth/1311867284.416106.png
1311867284.449514 rgb/1311867284.449514.png 1311867284.443699 depth/1311867284.443699.png
1311867284.485419 rgb/1311867284.485419.png 1311867284.482748 depth/1311867284.482748.png
1311867284.517730 rgb/1311867284.517730.png 1311867284.514261 depth/1311867284.514261.png
1311867284.549454 rgb/1311867284.549454.png 1311867284.544207 depth/1311867284.544207.png
1311867284.585418 rgb/1311867284.585418.png 1311867284.582664 depth/1311867284.582664.png
1311867284.617494 rgb/1311867284.617494.png 1311867284.612546 depth/1311867284.612546.png
1311867284.649523 rgb/1311867284.649523.png 1311867284.643869 depth/1311867284.643869.png
1311867284.685378 rgb/1311867284.685378.png 1311867284.679455 depth/1311867284.679455.png
1311867284.717486 rgb/1311867284.717486.png 1311867284.714820 depth/1311867284.714820.png
1311867284.749751 rgb/1311867284.749751.png 1311867284.749866 depth/1311867284.749866.png
1311867284.785409 rgb/1311867284.785409.png 1311867284.783227 depth/1311867284.783227.png
1311867284.818692 rgb/1311867284.818692.png 1311867284.813016 depth/1311867284.813016.png
1311867284.849277 rgb/1311867284.849277.png 1311867284.847988 depth/1311867284.847988.png
1311867284.885385 rgb/1311867284.885385.png 1311867284.882004 depth/1311867284.882004.png
1311867284.917461 rgb/1311867284.917461.png 1311867284.913002 depth/1311867284.913002.png
1311867284.949247 rgb/1311867284.949247.png 1311867284.948813 depth/1311867284.948813.png
1311867284.985258 rgb/1311867284.985258.png 1311867284.981655 depth/1311867284.981655.png
1311867285.017539 rgb/1311867285.017539.png 1311867285.011727 depth/1311867285.011727.png
1311867285.049368 rgb/1311867285.049368.png 1311867285.047501 depth/1311867285.047501.png
1311867285.085326 rgb/1311867285.085326.png 1311867285.082783 depth/1311867285.082783.png
1311867285.117712 rgb/1311867285.117712.png 1311867285.113140 depth/1311867285.113140.png
1311867285.150212 rgb/1311867285.150212.png 1311867285.150275 depth/1311867285.150275.png
1311867285.185580 rgb/1311867285.185580.png 1311867285.180224 depth/1311867285.180224.png
1311867285.218761 rgb/1311867285.218761.png 1311867285.212983 depth/1311867285.212983.png
1311867285.249366 rgb/1311867285.249366.png 1311867285.248852 depth/1311867285.248852.png
1311867285.285362 rgb/1311867285.285362.png 1311867285.282035 depth/1311867285.282035.png
1311867285.317503 rgb/1311867285.317503.png 1311867285.311875 depth/1311867285.311875.png
1311867285.349345 rgb/1311867285.349345.png 1311867285.349228 depth/1311867285.349228.png
1311867285.385541 rgb/1311867285.385541.png 1311867285.380239 depth/1311867285.380239.png
1311867285.417581 rgb/1311867285.417581.png 1311867285.411467 depth/1311867285.411467.png
1311867285.449284 rgb/1311867285.449284.png 1311867285.448322 depth/1311867285.448322.png
1311867285.485380 rgb/1311867285.485380.png 1311867285.479973 depth/1311867285.479973.png
1311867285.517648 rgb/1311867285.517648.png 1311867285.512012 depth/1311867285.512012.png
1311867285.549451 rgb/1311867285.549451.png 1311867285.549459 depth/1311867285.549459.png
1311867285.585574 rgb/1311867285.585574.png 1311867285.580140 depth/1311867285.580140.png
1311867285.617551 rgb/1311867285.617551.png 1311867285.612426 depth/1311867285.612426.png
1311867285.649403 rgb/1311867285.649403.png 1311867285.648790 depth/1311867285.648790.png
1311867285.685653 rgb/1311867285.685653.png 1311867285.680842 depth/1311867285.680842.png
1311867285.717719 rgb/1311867285.717719.png 1311867285.713476 depth/1311867285.713476.png
1311867285.749708 rgb/1311867285.749708.png 1311867285.749738 depth/1311867285.749738.png
1311867285.785478 rgb/1311867285.785478.png 1311867285.779481 depth/1311867285.779481.png
1311867285.817971 rgb/1311867285.817971.png 1311867285.814467 depth/1311867285.814467.png
1311867285.849628 rgb/1311867285.849628.png 1311867285.849623 depth/1311867285.849623.png
1311867285.885286 rgb/1311867285.885286.png 1311867285.879509 depth/1311867285.879509.png
1311867285.918737 rgb/1311867285.918737.png 1311867285.911572 depth/1311867285.911572.png
1311867285.949513 rgb/1311867285.949513.png 1311867285.949693 depth/1311867285.949693.png
1311867285.985836 rgb/1311867285.985836.png 1311867285.980474 depth/1311867285.980474.png
1311867286.018456 rgb/1311867286.018456.png 1311867286.018470 depth/1311867286.018470.png
1311867286.049422 rgb/1311867286.049422.png 1311867286.047399 depth/1311867286.047399.png
1311867286.085402 rgb/1311867286.085402.png 1311867286.079452 depth/1311867286.079452.png
1311867286.124098 rgb/1311867286.124098.png 1311867286.115849 depth/1311867286.115849.png
1311867286.150632 rgb/1311867286.150632.png 1311867286.149347 depth/1311867286.149347.png
1311867286.185759 rgb/1311867286.185759.png 1311867286.179991 depth/1311867286.179991.png
1311867286.217983 rgb/1311867286.217983.png 1311867286.216056 depth/1311867286.216056.png
1311867286.252521 rgb/1311867286.252521.png 1311867286.251559 depth/1311867286.251559.png
1311867286.286163 rgb/1311867286.286163.png 1311867286.283292 depth/1311867286.283292.png
1311867286.320349 rgb/1311867286.320349.png 1311867286.320352 depth/1311867286.320352.png
1311867286.352378 rgb/1311867286.352378.png 1311867286.352432 depth/1311867286.352432.png
1311867286.385563 rgb/1311867286.385563.png 1311867286.384776 depth/1311867286.384776.png
1311867286.417777 rgb/1311867286.417777.png 1311867286.415744 depth/1311867286.415744.png
1311867286.449420 rgb/1311867286.449420.png 1311867286.447630 depth/1311867286.447630.png
1311867286.485571 rgb/1311867286.485571.png 1311867286.479573 depth/1311867286.479573.png
1311867286.519022 rgb/1311867286.519022.png 1311867286.519037 depth/1311867286.519037.png
1311867286.551199 rgb/1311867286.551199.png 1311867286.551216 depth/1311867286.551216.png
1311867286.585520 rgb/1311867286.585520.png 1311867286.583881 depth/1311867286.583881.png
1311867286.619073 rgb/1311867286.619073.png 1311867286.619082 depth/1311867286.619082.png
1311867286.649991 rgb/1311867286.649991.png 1311867286.650006 depth/1311867286.650006.png
1311867286.685643 rgb/1311867286.685643.png 1311867286.679768 depth/1311867286.679768.png
1311867286.717616 rgb/1311867286.717616.png 1311867286.715446 depth/1311867286.715446.png
1311867286.749549 rgb/1311867286.749549.png 1311867286.747761 depth/1311867286.747761.png
1311867286.785646 rgb/1311867286.785646.png 1311867286.780410 depth/1311867286.780410.png
1311867286.817626 rgb/1311867286.817626.png 1311867286.815445 depth/1311867286.815445.png
1311867286.853582 rgb/1311867286.853582.png 1311867286.849774 depth/1311867286.849774.png
1311867286.886815 rgb/1311867286.886815.png 1311867286.879639 depth/1311867286.879639.png
1311867286.917438 rgb/1311867286.917438.png 1311867286.916996 depth/1311867286.916996.png
1311867286.954361 rgb/1311867286.954361.png 1311867286.947955 depth/1311867286.947955.png
1311867286.985412 rgb/1311867286.985412.png 1311867286.984719 depth/1311867286.984719.png
1311867287.017431 rgb/1311867287.017431.png 1311867287.016126 depth/1311867287.016126.png
1311867287.054702 rgb/1311867287.054702.png 1311867287.047992 depth/1311867287.047992.png
1311867287.085686 rgb/1311867287.085686.png 1311867287.080476 depth/1311867287.080476.png
1311867287.117817 rgb/1311867287.117817.png 1311867287.117822 depth/1311867287.117822.png
1311867287.153705 rgb/1311867287.153705.png 1311867287.149599 depth/1311867287.149599.png
1311867287.187445 rgb/1311867287.187445.png 1311867287.184349 depth/1311867287.184349.png
1311867287.217558 rgb/1311867287.217558.png 1311867287.215525 depth/1311867287.215525.png
1311867287.253668 rgb/1311867287.253668.png 1311867287.247482 depth/1311867287.247482.png
1311867287.287011 rgb/1311867287.287011.png 1311867287.287022 depth/1311867287.287022.png
1311867287.317563 rgb/1311867287.317563.png 1311867287.315527 depth/1311867287.315527.png
1311867287.354094 rgb/1311867287.354094.png 1311867287.349484 depth/1311867287.349484.png
1311867287.385542 rgb/1311867287.385542.png 1311867287.385554 depth/1311867287.385554.png
1311867287.417576 rgb/1311867287.417576.png 1311867287.416759 depth/1311867287.416759.png
1311867287.453529 rgb/1311867287.453529.png 1311867287.447562 depth/1311867287.447562.png
1311867287.486720 rgb/1311867287.486720.png 1311867287.486731 depth/1311867287.486731.png
1311867287.517500 rgb/1311867287.517500.png 1311867287.515489 depth/1311867287.515489.png
1311867287.553487 rgb/1311867287.553487.png 1311867287.550817 depth/1311867287.550817.png
1311867287.586854 rgb/1311867287.586854.png 1311867287.586952 depth/1311867287.586952.png
1311867287.617657 rgb/1311867287.617657.png 1311867287.617309 depth/1311867287.617309.png
1311867287.653916 rgb/1311867287.653916.png 1311867287.647862 depth/1311867287.647862.png
1311867287.687566 rgb/1311867287.687566.png 1311867287.684357 depth/1311867287.684357.png
1311867287.717628 rgb/1311867287.717628.png 1311867287.717048 depth/1311867287.717048.png
1311867287.755391 rgb/1311867287.755391.png 1311867287.749794 depth/1311867287.749794.png
1311867287.787243 rgb/1311867287.787243.png 1311867287.785349 depth/1311867287.785349.png
1311867287.826010 rgb/1311867287.826010.png 1311867287.818614 depth/1311867287.818614.png
1311867287.853651 rgb/1311867287.853651.png 1311867287.850417 depth/1311867287.850417.png
1311867287.893111 rgb/1311867287.893111.png 1311867287.884625 depth/1311867287.884625.png
1311867287.917571 rgb/1311867287.917571.png 1311867287.917157 depth/1311867287.917157.png
1311867287.953561 rgb/1311867287.953561.png 1311867287.948611 depth/1311867287.948611.png
1311867287.986839 rgb/1311867287.986839.png 1311867287.986852 depth/1311867287.986852.png
1311867288.017882 rgb/1311867288.017882.png 1311867288.016660 depth/1311867288.016660.png
1311867288.053639 rgb/1311867288.053639.png 1311867288.048741 depth/1311867288.048741.png
1311867288.085418 rgb/1311867288.085418.png 1311867288.084402 depth/1311867288.084402.png
1311867288.117594 rgb/1311867288.117594.png 1311867288.116353 depth/1311867288.116353.png
1311867288.154082 rgb/1311867288.154082.png 1311867288.148478 depth/1311867288.148478.png
1311867288.185455 rgb/1311867288.185455.png 1311867288.184693 depth/1311867288.184693.png
1311867288.217534 rgb/1311867288.217534.png 1311867288.217329 depth/1311867288.217329.png
1311867288.253581 rgb/1311867288.253581.png 1311867288.249817 depth/1311867288.249817.png
1311867288.285472 rgb/1311867288.285472.png 1311867288.284842 depth/1311867288.284842.png
1311867288.317583 rgb/1311867288.317583.png 1311867288.315892 depth/1311867288.315892.png
1311867288.353521 rgb/1311867288.353521.png 1311867288.349200 depth/1311867288.349200.png
1311867288.385883 rgb/1311867288.385883.png 1311867288.385889 depth/1311867288.385889.png
1311867288.417761 rgb/1311867288.417761.png 1311867288.416471 depth/1311867288.416471.png
1311867288.456019 rgb/1311867288.456019.png 1311867288.456030 depth/1311867288.456030.png
1311867288.485465 rgb/1311867288.485465.png 1311867288.483975 depth/1311867288.483975.png
1311867288.517689 rgb/1311867288.517689.png 1311867288.515938 depth/1311867288.515938.png
1311867288.554472 rgb/1311867288.554472.png 1311867288.554493 depth/1311867288.554493.png
1311867288.586600 rgb/1311867288.586600.png 1311867288.587434 depth/1311867288.587434.png
1311867288.617541 rgb/1311867288.617541.png 1311867288.617059 depth/1311867288.617059.png
1311867288.655102 rgb/1311867288.655102.png 1311867288.655120 depth/1311867288.655120.png
1311867288.687379 rgb/1311867288.687379.png 1311867288.687411 depth/1311867288.687411.png
1311867288.717702 rgb/1311867288.717702.png 1311867288.717718 depth/1311867288.717718.png
1311867288.756022 rgb/1311867288.756022.png 1311867288.756066 depth/1311867288.756066.png
1311867288.785509 rgb/1311867288.785509.png 1311867288.784216 depth/1311867288.784216.png
1311867288.819223 rgb/1311867288.819223.png 1311867288.819240 depth/1311867288.819240.png
1311867288.854331 rgb/1311867288.854331.png 1311867288.854345 depth/1311867288.854345.png
1311867288.885556 rgb/1311867288.885556.png 1311867288.883768 depth/1311867288.883768.png
1311867288.917612 rgb/1311867288.917612.png 1311867288.915649 depth/1311867288.915649.png
1311867288.954939 rgb/1311867288.954939.png 1311867288.959948 depth/1311867288.959948.png
1311867288.985592 rgb/1311867288.985592.png 1311867288.984724 depth/1311867288.984724.png
1311867289.017656 rgb/1311867289.017656.png 1311867289.015746 depth/1311867289.015746.png
1311867289.053512 rgb/1311867289.053512.png 1311867289.051995 depth/1311867289.051995.png
1311867289.085511 rgb/1311867289.085511.png 1311867289.084565 depth/1311867289.084565.png
1311867289.117543 rgb/1311867289.117543.png 1311867289.116004 depth/1311867289.116004.png
1311867289.154583 rgb/1311867289.154583.png 1311867289.154593 depth/1311867289.154593.png
1311867289.185640 rgb/1311867289.185640.png 1311867289.184904 depth/1311867289.184904.png
1311867289.218482 rgb/1311867289.218482.png 1311867289.218506 depth/1311867289.218506.png
1311867289.255039 rgb/1311867289.255039.png 1311867289.255048 depth/1311867289.255048.png
1311867289.285387 rgb/1311867289.285387.png 1311867289.284501 depth/1311867289.284501.png
1311867289.317629 rgb/1311867289.317629.png 1311867289.315842 depth/1311867289.315842.png
1311867289.353909 rgb/1311867289.353909.png 1311867289.353917 depth/1311867289.353917.png
1311867289.386185 rgb/1311867289.386185.png 1311867289.386190 depth/1311867289.386190.png
1311867289.417704 rgb/1311867289.417704.png 1311867289.415781 depth/1311867289.415781.png
1311867289.453606 rgb/1311867289.453606.png 1311867289.452549 depth/1311867289.452549.png
1311867289.485961 rgb/1311867289.485961.png 1311867289.485967 depth/1311867289.485967.png
1311867289.518318 rgb/1311867289.518318.png 1311867289.518324 depth/1311867289.518324.png
1311867289.554869 rgb/1311867289.554869.png 1311867289.554882 depth/1311867289.554882.png
1311867289.585613 rgb/1311867289.585613.png 1311867289.584817 depth/1311867289.584817.png
1311867289.617649 rgb/1311867289.617649.png 1311867289.615707 depth/1311867289.615707.png
1311867289.653639 rgb/1311867289.653639.png 1311867289.651631 depth/1311867289.651631.png
1311867289.685685 rgb/1311867289.685685.png 1311867289.683686 depth/1311867289.683686.png
1311867289.720426 rgb/1311867289.720426.png 1311867289.720435 depth/1311867289.720435.png
1311867289.756408 rgb/1311867289.756408.png 1311867289.756418 depth/1311867289.756418.png
1311867289.785568 rgb/1311867289.785568.png 1311867289.783898 depth/1311867289.783898.png
1311867289.824026 rgb/1311867289.824026.png 1311867289.824037 depth/1311867289.824037.png
1311867289.854176 rgb/1311867289.854176.png 1311867289.854187 depth/1311867289.854187.png
1311867289.885568 rgb/1311867289.885568.png 1311867289.884044 depth/1311867289.884044.png
1311867289.920046 rgb/1311867289.920046.png 1311867289.920053 depth/1311867289.920053.png
1311867289.953641 rgb/1311867289.953641.png 1311867289.952577 depth/1311867289.952577.png
1311867289.985528 rgb/1311867289.985528.png 1311867289.984236 depth/1311867289.984236.png
1311867290.020153 rgb/1311867290.020153.png 1311867290.023217 depth/1311867290.023217.png
1311867290.053575 rgb/1311867290.053575.png 1311867290.053591 depth/1311867290.053591.png
1311867290.085474 rgb/1311867290.085474.png 1311867290.083953 depth/1311867290.083953.png
1311867290.124880 rgb/1311867290.124880.png 1311867290.121521 depth/1311867290.121521.png
1311867290.153612 rgb/1311867290.153612.png 1311867290.153221 depth/1311867290.153221.png
1311867290.185638 rgb/1311867290.185638.png 1311867290.184926 depth/1311867290.184926.png
1311867290.222529 rgb/1311867290.222529.png 1311867290.222549 depth/1311867290.222549.png
1311867290.254027 rgb/1311867290.254027.png 1311867290.254032 depth/1311867290.254032.png
1311867290.286994 rgb/1311867290.286994.png 1311867290.289238 depth/1311867290.289238.png
1311867290.322046 rgb/1311867290.322046.png 1311867290.322075 depth/1311867290.322075.png
1311867290.354777 rgb/1311867290.354777.png 1311867290.358779 depth/1311867290.358779.png
1311867290.386415 rgb/1311867290.386415.png 1311867290.386424 depth/1311867290.386424.png
1311867290.421620 rgb/1311867290.421620.png 1311867290.421632 depth/1311867290.421632.png
1311867290.457663 rgb/1311867290.457663.png 1311867290.457839 depth/1311867290.457839.png
1311867290.485984 rgb/1311867290.485984.png 1311867290.485995 depth/1311867290.485995.png
1311867290.522328 rgb/1311867290.522328.png 1311867290.522340 depth/1311867290.522340.png
1311867290.553706 rgb/1311867290.553706.png 1311867290.553428 depth/1311867290.553428.png
1311867290.585554 rgb/1311867290.585554.png 1311867290.585047 depth/1311867290.585047.png
1311867290.620155 rgb/1311867290.620155.png 1311867290.622102 depth/1311867290.622102.png
1311867290.653602 rgb/1311867290.653602.png 1311867290.652320 depth/1311867290.652320.png
1311867290.685718 rgb/1311867290.685718.png 1311867290.685753 depth/1311867290.685753.png
1311867290.725606 rgb/1311867290.725606.png 1311867290.725615 depth/1311867290.725615.png
1311867290.753974 rgb/1311867290.753974.png 1311867290.752306 depth/1311867290.752306.png
1311867290.786574 rgb/1311867290.786574.png 1311867290.786606 depth/1311867290.786606.png
1311867290.823128 rgb/1311867290.823128.png 1311867290.823172 depth/1311867290.823172.png
1311867290.855586 rgb/1311867290.855586.png 1311867290.855604 depth/1311867290.855604.png
1311867290.887678 rgb/1311867290.887678.png 1311867290.887699 depth/1311867290.887699.png
1311867290.922693 rgb/1311867290.922693.png 1311867290.922712 depth/1311867290.922712.png
1311867290.953711 rgb/1311867290.953711.png 1311867290.952067 depth/1311867290.952067.png
1311867290.990676 rgb/1311867290.990676.png 1311867290.990691 depth/1311867290.990691.png
1311867291.023910 rgb/1311867291.023910.png 1311867291.023929 depth/1311867291.023929.png
1311867291.055820 rgb/1311867291.055820.png 1311867291.051871 depth/1311867291.051871.png
1311867291.090338 rgb/1311867291.090338.png 1311867291.093482 depth/1311867291.093482.png
1311867291.120272 rgb/1311867291.120272.png 1311867291.120311 depth/1311867291.120311.png
1311867291.154182 rgb/1311867291.154182.png 1311867291.154189 depth/1311867291.154189.png
1311867291.189179 rgb/1311867291.189179.png 1311867291.189199 depth/1311867291.189199.png
1311867291.221074 rgb/1311867291.221074.png 1311867291.221101 depth/1311867291.221101.png
1311867291.254380 rgb/1311867291.254380.png 1311867291.254391 depth/1311867291.254391.png
1311867291.287791 rgb/1311867291.287791.png 1311867291.287796 depth/1311867291.287796.png
1311867291.321060 rgb/1311867291.321060.png 1311867291.321090 depth/1311867291.321090.png
1311867291.354784 rgb/1311867291.354784.png 1311867291.354796 depth/1311867291.354796.png
1311867291.387834 rgb/1311867291.387834.png 1311867291.387876 depth/1311867291.387876.png
1311867291.422316 rgb/1311867291.422316.png 1311867291.422335 depth/1311867291.422335.png
1311867291.453656 rgb/1311867291.453656.png 1311867291.452372 depth/1311867291.452372.png
1311867291.488381 rgb/1311867291.488381.png 1311867291.488400 depth/1311867291.488400.png
1311867291.520140 rgb/1311867291.520140.png 1311867291.520173 depth/1311867291.520173.png
1311867291.553645 rgb/1311867291.553645.png 1311867291.552383 depth/1311867291.552383.png
1311867291.589498 rgb/1311867291.589498.png 1311867291.589508 depth/1311867291.589508.png
1311867291.620673 rgb/1311867291.620673.png 1311867291.620687 depth/1311867291.620687.png
1311867291.653970 rgb/1311867291.653970.png 1311867291.653978 depth/1311867291.653978.png
1311867291.689647 rgb/1311867291.689647.png 1311867291.689681 depth/1311867291.689681.png
1311867291.720251 rgb/1311867291.720251.png 1311867291.720274 depth/1311867291.720274.png
1311867291.753718 rgb/1311867291.753718.png 1311867291.752562 depth/1311867291.752562.png
1311867291.788985 rgb/1311867291.788985.png 1311867291.789002 depth/1311867291.789002.png
1311867291.821719 rgb/1311867291.821719.png 1311867291.821548 depth/1311867291.821548.png
1311867291.853864 rgb/1311867291.853864.png 1311867291.851921 depth/1311867291.851921.png
1311867291.887943 rgb/1311867291.887943.png 1311867291.887949 depth/1311867291.887949.png
1311867291.920685 rgb/1311867291.920685.png 1311867291.920693 depth/1311867291.920693.png
1311867291.953720 rgb/1311867291.953720.png 1311867291.951900 depth/1311867291.951900.png
1311867291.990091 rgb/1311867291.990091.png 1311867291.990289 depth/1311867291.990289.png
1311867292.022520 rgb/1311867292.022520.png 1311867292.022526 depth/1311867292.022526.png
1311867292.053683 rgb/1311867292.053683.png 1311867292.052577 depth/1311867292.052577.png
1311867292.092254 rgb/1311867292.092254.png 1311867292.092285 depth/1311867292.092285.png
1311867292.124382 rgb/1311867292.124382.png 1311867292.124388 depth/1311867292.124388.png
1311867292.160249 rgb/1311867292.160249.png 1311867292.160265 depth/1311867292.160265.png
1311867292.189973 rgb/1311867292.189973.png 1311867292.189985 depth/1311867292.189985.png
1311867292.220732 rgb/1311867292.220732.png 1311867292.220742 depth/1311867292.220742.png
1311867292.257685 rgb/1311867292.257685.png 1311867292.257691 depth/1311867292.257691.png
1311867292.287816 rgb/1311867292.287816.png 1311867292.287827 depth/1311867292.287827.png
1311867292.321387 rgb/1311867292.321387.png 1311867292.321727 depth/1311867292.321727.png
1311867292.362160 rgb/1311867292.362160.png 1311867292.362171 depth/1311867292.362171.png
1311867292.395350 rgb/1311867292.395350.png 1311867292.395362 depth/1311867292.395362.png
1311867292.425930 rgb/1311867292.425930.png 1311867292.421631 depth/1311867292.421631.png
1311867292.456448 rgb/1311867292.456448.png 1311867292.456521 depth/1311867292.456521.png
1311867292.488351 rgb/1311867292.488351.png 1311867292.488370 depth/1311867292.488370.png
1311867292.522883 rgb/1311867292.522883.png 1311867292.522965 depth/1311867292.522965.png
1311867292.558104 rgb/1311867292.558104.png 1311867292.558115 depth/1311867292.558115.png
1311867292.588222 rgb/1311867292.588222.png 1311867292.588244 depth/1311867292.588244.png
1311867292.623076 rgb/1311867292.623076.png 1311867292.623087 depth/1311867292.623087.png
1311867292.659508 rgb/1311867292.659508.png 1311867292.659521 depth/1311867292.659521.png
1311867292.688015 rgb/1311867292.688015.png 1311867292.688022 depth/1311867292.688022.png
1311867292.720644 rgb/1311867292.720644.png 1311867292.720697 depth/1311867292.720697.png
1311867292.756178 rgb/1311867292.756178.png 1311867292.756188 depth/1311867292.756188.png
================================================
FILE: Examples/RGB-D/associations/fr3_nstr_tex_near.txt
================================================
1341840083.789974 rgb/1341840083.789974.png 1341840083.790018 depth/1341840083.790018.png
1341840083.821987 rgb/1341840083.821987.png 1341840083.822003 depth/1341840083.822003.png
1341840083.858104 rgb/1341840083.858104.png 1341840083.858138 depth/1341840083.858138.png
1341840083.890155 rgb/1341840083.890155.png 1341840083.890192 depth/1341840083.890192.png
1341840083.926071 rgb/1341840083.926071.png 1341840083.926530 depth/1341840083.926530.png
1341840083.958095 rgb/1341840083.958095.png 1341840083.958118 depth/1341840083.958118.png
1341840083.990000 rgb/1341840083.990000.png 1341840083.990077 depth/1341840083.990077.png
1341840084.026121 rgb/1341840084.026121.png 1341840084.026139 depth/1341840084.026139.png
1341840084.057936 rgb/1341840084.057936.png 1341840084.057949 depth/1341840084.057949.png
1341840084.090022 rgb/1341840084.090022.png 1341840084.090034 depth/1341840084.090034.png
1341840084.126053 rgb/1341840084.126053.png 1341840084.126067 depth/1341840084.126067.png
1341840084.158032 rgb/1341840084.158032.png 1341840084.158058 depth/1341840084.158058.png
1341840084.194127 rgb/1341840084.194127.png 1341840084.194663 depth/1341840084.194663.png
1341840084.226042 rgb/1341840084.226042.png 1341840084.226061 depth/1341840084.226061.png
1341840084.258027 rgb/1341840084.258027.png 1341840084.258043 depth/1341840084.258043.png
1341840084.294117 rgb/1341840084.294117.png 1341840084.294139 depth/1341840084.294139.png
1341840084.325994 rgb/1341840084.325994.png 1341840084.326013 depth/1341840084.326013.png
1341840084.358007 rgb/1341840084.358007.png 1341840084.358030 depth/1341840084.358030.png
1341840084.394092 rgb/1341840084.394092.png 1341840084.394197 depth/1341840084.394197.png
1341840084.425964 rgb/1341840084.425964.png 1341840084.426034 depth/1341840084.426034.png
1341840084.462012 rgb/1341840084.462012.png 1341840084.462028 depth/1341840084.462028.png
1341840084.494007 rgb/1341840084.494007.png 1341840084.494016 depth/1341840084.494016.png
1341840084.525979 rgb/1341840084.525979.png 1341840084.525994 depth/1341840084.525994.png
1341840084.562039 rgb/1341840084.562039.png 1341840084.562045 depth/1341840084.562045.png
1341840084.594095 rgb/1341840084.594095.png 1341840084.594109 depth/1341840084.594109.png
1341840084.626070 rgb/1341840084.626070.png 1341840084.626115 depth/1341840084.626115.png
1341840084.661961 rgb/1341840084.661961.png 1341840084.661999 depth/1341840084.661999.png
1341840084.694181 rgb/1341840084.694181.png 1341840084.694201 depth/1341840084.694201.png
1341840084.729879 rgb/1341840084.729879.png 1341840084.729901 depth/1341840084.729901.png
1341840084.762054 rgb/1341840084.762054.png 1341840084.762071 depth/1341840084.762071.png
1341840084.794567 rgb/1341840084.794567.png 1341840084.794582 depth/1341840084.794582.png
1341840084.829914 rgb/1341840084.829914.png 1341840084.829933 depth/1341840084.829933.png
1341840084.861905 rgb/1341840084.861905.png 1341840084.861922 depth/1341840084.861922.png
1341840084.894025 rgb/1341840084.894025.png 1341840084.894044 depth/1341840084.894044.png
1341840084.929921 rgb/1341840084.929921.png 1341840084.929951 depth/1341840084.929951.png
1341840084.962026 rgb/1341840084.962026.png 1341840084.962051 depth/1341840084.962051.png
1341840084.998375 rgb/1341840084.998375.png 1341840084.998394 depth/1341840084.998394.png
1341840085.030745 rgb/1341840085.030745.png 1341840085.030775 depth/1341840085.030775.png
1341840085.062049 rgb/1341840085.062049.png 1341840085.062066 depth/1341840085.062066.png
1341840085.097991 rgb/1341840085.097991.png 1341840085.098025 depth/1341840085.098025.png
1341840085.130028 rgb/1341840085.130028.png 1341840085.130116 depth/1341840085.130116.png
1341840085.166080 rgb/1341840085.166080.png 1341840085.166127 depth/1341840085.166127.png
1341840085.198124 rgb/1341840085.198124.png 1341840085.198154 depth/1341840085.198154.png
1341840085.230345 rgb/1341840085.230345.png 1341840085.230963 depth/1341840085.230963.png
1341840085.266025 rgb/1341840085.266025.png 1341840085.266044 depth/1341840085.266044.png
1341840085.298250 rgb/1341840085.298250.png 1341840085.298266 depth/1341840085.298266.png
1341840085.330214 rgb/1341840085.330214.png 1341840085.330767 depth/1341840085.330767.png
1341840085.366055 rgb/1341840085.366055.png 1341840085.366076 depth/1341840085.366076.png
1341840085.398022 rgb/1341840085.398022.png 1341840085.398050 depth/1341840085.398050.png
1341840085.433967 rgb/1341840085.433967.png 1341840085.433975 depth/1341840085.433975.png
1341840085.465998 rgb/1341840085.465998.png 1341840085.466036 depth/1341840085.466036.png
1341840085.498029 rgb/1341840085.498029.png 1341840085.498043 depth/1341840085.498043.png
1341840085.533945 rgb/1341840085.533945.png 1341840085.533966 depth/1341840085.533966.png
1341840085.598078 rgb/1341840085.598078.png 1341840085.598105 depth/1341840085.598105.png
1341840085.634035 rgb/1341840085.634035.png 1341840085.634047 depth/1341840085.634047.png
1341840085.666062 rgb/1341840085.666062.png 1341840085.666093 depth/1341840085.666093.png
1341840085.701946 rgb/1341840085.701946.png 1341840085.701981 depth/1341840085.701981.png
1341840085.734314 rgb/1341840085.734314.png 1341840085.734325 depth/1341840085.734325.png
1341840085.773194 rgb/1341840085.773194.png 1341840085.773226 depth/1341840085.773226.png
1341840085.805306 rgb/1341840085.805306.png 1341840085.805955 depth/1341840085.805955.png
1341840085.840976 rgb/1341840085.840976.png 1341840085.840995 depth/1341840085.840995.png
1341840085.873132 rgb/1341840085.873132.png 1341840085.873154 depth/1341840085.873154.png
1341840085.904912 rgb/1341840085.904912.png 1341840085.905360 depth/1341840085.905360.png
1341840085.940930 rgb/1341840085.940930.png 1341840085.940965 depth/1341840085.940965.png
1341840085.972968 rgb/1341840085.972968.png 1341840085.972992 depth/1341840085.972992.png
1341840086.009063 rgb/1341840086.009063.png 1341840086.009089 depth/1341840086.009089.png
1341840086.040942 rgb/1341840086.040942.png 1341840086.040951 depth/1341840086.040951.png
1341840086.073092 rgb/1341840086.073092.png 1341840086.073107 depth/1341840086.073107.png
1341840086.109086 rgb/1341840086.109086.png 1341840086.109111 depth/1341840086.109111.png
1341840086.141084 rgb/1341840086.141084.png 1341840086.141513 depth/1341840086.141513.png
1341840086.177243 rgb/1341840086.177243.png 1341840086.177256 depth/1341840086.177256.png
1341840086.209221 rgb/1341840086.209221.png 1341840086.209241 depth/1341840086.209241.png
1341840086.240929 rgb/1341840086.240929.png 1341840086.240954 depth/1341840086.240954.png
1341840086.277032 rgb/1341840086.277032.png 1341840086.277050 depth/1341840086.277050.png
1341840086.308978 rgb/1341840086.308978.png 1341840086.309003 depth/1341840086.309003.png
1341840086.345100 rgb/1341840086.345100.png 1341840086.345116 depth/1341840086.345116.png
1341840086.377020 rgb/1341840086.377020.png 1341840086.377543 depth/1341840086.377543.png
1341840086.408991 rgb/1341840086.408991.png 1341840086.409007 depth/1341840086.409007.png
1341840086.445193 rgb/1341840086.445193.png 1341840086.445224 depth/1341840086.445224.png
1341840086.476977 rgb/1341840086.476977.png 1341840086.476991 depth/1341840086.476991.png
1341840086.512947 rgb/1341840086.512947.png 1341840086.513525 depth/1341840086.513525.png
1341840086.545033 rgb/1341840086.545033.png 1341840086.545042 depth/1341840086.545042.png
1341840086.577127 rgb/1341840086.577127.png 1341840086.577145 depth/1341840086.577145.png
1341840086.612988 rgb/1341840086.612988.png 1341840086.613003 depth/1341840086.613003.png
1341840086.645038 rgb/1341840086.645038.png 1341840086.645050 depth/1341840086.645050.png
1341840086.680940 rgb/1341840086.680940.png 1341840086.680951 depth/1341840086.680951.png
1341840086.712983 rgb/1341840086.712983.png 1341840086.712996 depth/1341840086.712996.png
1341840086.745031 rgb/1341840086.745031.png 1341840086.745043 depth/1341840086.745043.png
1341840086.781079 rgb/1341840086.781079.png 1341840086.781094 depth/1341840086.781094.png
1341840086.813143 rgb/1341840086.813143.png 1341840086.813160 depth/1341840086.813160.png
1341840086.845112 rgb/1341840086.845112.png 1341840086.845127 depth/1341840086.845127.png
1341840086.880946 rgb/1341840086.880946.png 1341840086.880957 depth/1341840086.880957.png
1341840086.913039 rgb/1341840086.913039.png 1341840086.913832 depth/1341840086.913832.png
1341840086.949088 rgb/1341840086.949088.png 1341840086.949109 depth/1341840086.949109.png
1341840086.981130 rgb/1341840086.981130.png 1341840086.981142 depth/1341840086.981142.png
1341840087.013086 rgb/1341840087.013086.png 1341840087.013094 depth/1341840087.013094.png
1341840087.048951 rgb/1341840087.048951.png 1341840087.048991 depth/1341840087.048991.png
1341840087.080960 rgb/1341840087.080960.png 1341840087.080972 depth/1341840087.080972.png
1341840087.114965 rgb/1341840087.114965.png 1341840087.114991 depth/1341840087.114991.png
1341840087.149068 rgb/1341840087.149068.png 1341840087.149100 depth/1341840087.149100.png
1341840087.210062 rgb/1341840087.210062.png 1341840087.210102 depth/1341840087.210102.png
1341840087.241973 rgb/1341840087.241973.png 1341840087.241986 depth/1341840087.241986.png
1341840087.274056 rgb/1341840087.274056.png 1341840087.275958 depth/1341840087.275958.png
1341840087.310014 rgb/1341840087.310014.png 1341840087.310083 depth/1341840087.310083.png
1341840087.342211 rgb/1341840087.342211.png 1341840087.342221 depth/1341840087.342221.png
1341840087.378005 rgb/1341840087.378005.png 1341840087.378083 depth/1341840087.378083.png
1341840087.410085 rgb/1341840087.410085.png 1341840087.410107 depth/1341840087.410107.png
1341840087.442030 rgb/1341840087.442030.png 1341840087.442092 depth/1341840087.442092.png
1341840087.478092 rgb/1341840087.478092.png 1341840087.478144 depth/1341840087.478144.png
1341840087.510068 rgb/1341840087.510068.png 1341840087.510082 depth/1341840087.510082.png
1341840087.542111 rgb/1341840087.542111.png 1341840087.542141 depth/1341840087.542141.png
1341840087.578022 rgb/1341840087.578022.png 1341840087.578058 depth/1341840087.578058.png
1341840087.609992 rgb/1341840087.609992.png 1341840087.610062 depth/1341840087.610062.png
1341840087.646285 rgb/1341840087.646285.png 1341840087.646292 depth/1341840087.646292.png
1341840087.677989 rgb/1341840087.677989.png 1341840087.678002 depth/1341840087.678002.png
1341840087.710009 rgb/1341840087.710009.png 1341840087.710022 depth/1341840087.710022.png
1341840087.746036 rgb/1341840087.746036.png 1341840087.746050 depth/1341840087.746050.png
1341840087.777950 rgb/1341840087.777950.png 1341840087.777959 depth/1341840087.777959.png
1341840087.809957 rgb/1341840087.809957.png 1341840087.809975 depth/1341840087.809975.png
1341840087.846059 rgb/1341840087.846059.png 1341840087.846080 depth/1341840087.846080.png
1341840087.878039 rgb/1341840087.878039.png 1341840087.878062 depth/1341840087.878062.png
1341840087.914037 rgb/1341840087.914037.png 1341840087.914047 depth/1341840087.914047.png
1341840087.946068 rgb/1341840087.946068.png 1341840087.946621 depth/1341840087.946621.png
1341840087.978064 rgb/1341840087.978064.png 1341840087.978232 depth/1341840087.978232.png
1341840088.013958 rgb/1341840088.013958.png 1341840088.013970 depth/1341840088.013970.png
1341840088.046096 rgb/1341840088.046096.png 1341840088.046923 depth/1341840088.046923.png
1341840088.077959 rgb/1341840088.077959.png 1341840088.077975 depth/1341840088.077975.png
1341840088.114105 rgb/1341840088.114105.png 1341840088.114119 depth/1341840088.114119.png
1341840088.146005 rgb/1341840088.146005.png 1341840088.146015 depth/1341840088.146015.png
1341840088.181986 rgb/1341840088.181986.png 1341840088.182027 depth/1341840088.182027.png
1341840088.214180 rgb/1341840088.214180.png 1341840088.214205 depth/1341840088.214205.png
1341840088.245999 rgb/1341840088.245999.png 1341840088.246064 depth/1341840088.246064.png
1341840088.281993 rgb/1341840088.281993.png 1341840088.282019 depth/1341840088.282019.png
1341840088.313975 rgb/1341840088.313975.png 1341840088.313991 depth/1341840088.313991.png
1341840088.350184 rgb/1341840088.350184.png 1341840088.350371 depth/1341840088.350371.png
1341840088.382124 rgb/1341840088.382124.png 1341840088.382139 depth/1341840088.382139.png
1341840088.414141 rgb/1341840088.414141.png 1341840088.414160 depth/1341840088.414160.png
1341840088.450005 rgb/1341840088.450005.png 1341840088.450023 depth/1341840088.450023.png
1341840088.481951 rgb/1341840088.481951.png 1341840088.481975 depth/1341840088.481975.png
1341840088.514195 rgb/1341840088.514195.png 1341840088.514426 depth/1341840088.514426.png
1341840088.550086 rgb/1341840088.550086.png 1341840088.550109 depth/1341840088.550109.png
1341840088.582210 rgb/1341840088.582210.png 1341840088.582232 depth/1341840088.582232.png
1341840088.618206 rgb/1341840088.618206.png 1341840088.618232 depth/1341840088.618232.png
1341840088.650101 rgb/1341840088.650101.png 1341840088.650115 depth/1341840088.650115.png
1341840088.682767 rgb/1341840088.682767.png 1341840088.682786 depth/1341840088.682786.png
1341840088.717920 rgb/1341840088.717920.png 1341840088.717928 depth/1341840088.717928.png
1341840088.750010 rgb/1341840088.750010.png 1341840088.750201 depth/1341840088.750201.png
1341840088.782091 rgb/1341840088.782091.png 1341840088.782122 depth/1341840088.782122.png
1341840088.818075 rgb/1341840088.818075.png 1341840088.818089 depth/1341840088.818089.png
1341840088.849999 rgb/1341840088.849999.png 1341840088.850007 depth/1341840088.850007.png
1341840088.886343 rgb/1341840088.886343.png 1341840088.886384 depth/1341840088.886384.png
1341840088.917961 rgb/1341840088.917961.png 1341840088.918002 depth/1341840088.918002.png
1341840088.950086 rgb/1341840088.950086.png 1341840088.950114 depth/1341840088.950114.png
1341840088.985936 rgb/1341840088.985936.png 1341840088.985949 depth/1341840088.985949.png
1341840089.018030 rgb/1341840089.018030.png 1341840089.018054 depth/1341840089.018054.png
1341840089.050058 rgb/1341840089.050058.png 1341840089.050079 depth/1341840089.050079.png
1341840089.086377 rgb/1341840089.086377.png 1341840089.086404 depth/1341840089.086404.png
1341840089.118898 rgb/1341840089.118898.png 1341840089.119091 depth/1341840089.119091.png
1341840089.155985 rgb/1341840089.155985.png 1341840089.159592 depth/1341840089.159592.png
1341840089.193015 rgb/1341840089.193015.png 1341840089.193046 depth/1341840089.193046.png
1341840089.225124 rgb/1341840089.225124.png 1341840089.225144 depth/1341840089.225144.png
1341840089.260996 rgb/1341840089.260996.png 1341840089.261019 depth/1341840089.261019.png
1341840089.292904 rgb/1341840089.292904.png 1341840089.292917 depth/1341840089.292917.png
1341840089.325058 rgb/1341840089.325058.png 1341840089.325074 depth/1341840089.325074.png
1341840089.360931 rgb/1341840089.360931.png 1341840089.360942 depth/1341840089.360942.png
1341840089.393209 rgb/1341840089.393209.png 1341840089.393227 depth/1341840089.393227.png
1341840089.428976 rgb/1341840089.428976.png 1341840089.428984 depth/1341840089.428984.png
1341840089.461193 rgb/1341840089.461193.png 1341840089.461206 depth/1341840089.461206.png
1341840089.493053 rgb/1341840089.493053.png 1341840089.493066 depth/1341840089.493066.png
1341840089.529041 rgb/1341840089.529041.png 1341840089.529048 depth/1341840089.529048.png
1341840089.561015 rgb/1341840089.561015.png 1341840089.561044 depth/1341840089.561044.png
1341840089.596989 rgb/1341840089.596989.png 1341840089.597026 depth/1341840089.597026.png
1341840089.629045 rgb/1341840089.629045.png 1341840089.629509 depth/1341840089.629509.png
1341840089.660977 rgb/1341840089.660977.png 1341840089.660987 depth/1341840089.660987.png
1341840089.697180 rgb/1341840089.697180.png 1341840089.697197 depth/1341840089.697197.png
1341840089.728954 rgb/1341840089.728954.png 1341840089.728966 depth/1341840089.728966.png
1341840089.761030 rgb/1341840089.761030.png 1341840089.761044 depth/1341840089.761044.png
1341840089.797194 rgb/1341840089.797194.png 1341840089.797210 depth/1341840089.797210.png
1341840089.828965 rgb/1341840089.828965.png 1341840089.828983 depth/1341840089.828983.png
1341840089.861003 rgb/1341840089.861003.png 1341840089.861015 depth/1341840089.861015.png
1341840089.897123 rgb/1341840089.897123.png 1341840089.897143 depth/1341840089.897143.png
1341840089.929407 rgb/1341840089.929407.png 1341840089.929420 depth/1341840089.929420.png
1341840089.960920 rgb/1341840089.960920.png 1341840089.960932 depth/1341840089.960932.png
1341840089.997889 rgb/1341840089.997889.png 1341840089.997906 depth/1341840089.997906.png
1341840090.029152 rgb/1341840090.029152.png 1341840090.029160 depth/1341840090.029160.png
1341840090.064979 rgb/1341840090.064979.png 1341840090.064993 depth/1341840090.064993.png
1341840090.097503 rgb/1341840090.097503.png 1341840090.097523 depth/1341840090.097523.png
1341840090.128972 rgb/1341840090.128972.png 1341840090.128986 depth/1341840090.128986.png
1341840090.165020 rgb/1341840090.165020.png 1341840090.165053 depth/1341840090.165053.png
1341840090.197048 rgb/1341840090.197048.png 1341840090.197068 depth/1341840090.197068.png
1341840090.229041 rgb/1341840090.229041.png 1341840090.229054 depth/1341840090.229054.png
1341840090.265032 rgb/1341840090.265032.png 1341840090.265054 depth/1341840090.265054.png
1341840090.297153 rgb/1341840090.297153.png 1341840090.297167 depth/1341840090.297167.png
1341840090.365109 rgb/1341840090.365109.png 1341840090.365179 depth/1341840090.365179.png
1341840090.426138 rgb/1341840090.426138.png 1341840090.426152 depth/1341840090.426152.png
1341840090.458131 rgb/1341840090.458131.png 1341840090.458145 depth/1341840090.458145.png
1341840090.494010 rgb/1341840090.494010.png 1341840090.494021 depth/1341840090.494021.png
1341840090.525928 rgb/1341840090.525928.png 1341840090.525942 depth/1341840090.525942.png
1341840090.562011 rgb/1341840090.562011.png 1341840090.562024 depth/1341840090.562024.png
1341840090.594146 rgb/1341840090.594146.png 1341840090.594158 depth/1341840090.594158.png
1341840090.625976 rgb/1341840090.625976.png 1341840090.625985 depth/1341840090.625985.png
1341840090.662197 rgb/1341840090.662197.png 1341840090.662243 depth/1341840090.662243.png
1341840090.694336 rgb/1341840090.694336.png 1341840090.694355 depth/1341840090.694355.png
1341840090.726017 rgb/1341840090.726017.png 1341840090.726035 depth/1341840090.726035.png
1341840090.762086 rgb/1341840090.762086.png 1341840090.762124 depth/1341840090.762124.png
1341840090.794081 rgb/1341840090.794081.png 1341840090.794103 depth/1341840090.794103.png
1341840090.830060 rgb/1341840090.830060.png 1341840090.830068 depth/1341840090.830068.png
1341840090.861960 rgb/1341840090.861960.png 1341840090.861972 depth/1341840090.861972.png
1341840090.894052 rgb/1341840090.894052.png 1341840090.894065 depth/1341840090.894065.png
1341840090.930027 rgb/1341840090.930027.png 1341840090.930046 depth/1341840090.930046.png
1341840090.962159 rgb/1341840090.962159.png 1341840090.962174 depth/1341840090.962174.png
1341840090.994115 rgb/1341840090.994115.png 1341840090.994127 depth/1341840090.994127.png
1341840091.030295 rgb/1341840091.030295.png 1341840091.030350 depth/1341840091.030350.png
1341840091.061986 rgb/1341840091.061986.png 1341840091.061998 depth/1341840091.061998.png
1341840091.097971 rgb/1341840091.097971.png 1341840091.097979 depth/1341840091.097979.png
1341840091.129998 rgb/1341840091.129998.png 1341840091.130012 depth/1341840091.130012.png
1341840091.162125 rgb/1341840091.162125.png 1341840091.162143 depth/1341840091.162143.png
1341840091.198103 rgb/1341840091.198103.png 1341840091.198712 depth/1341840091.198712.png
1341840091.230330 rgb/1341840091.230330.png 1341840091.230343 depth/1341840091.230343.png
1341840091.262411 rgb/1341840091.262411.png 1341840091.262432 depth/1341840091.262432.png
1341840091.298027 rgb/1341840091.298027.png 1341840091.298086 depth/1341840091.298086.png
1341840091.330057 rgb/1341840091.330057.png 1341840091.330074 depth/1341840091.330074.png
1341840091.366166 rgb/1341840091.366166.png 1341840091.366183 depth/1341840091.366183.png
1341840091.397935 rgb/1341840091.397935.png 1341840091.397951 depth/1341840091.397951.png
1341840091.430154 rgb/1341840091.430154.png 1341840091.430166 depth/1341840091.430166.png
1341840091.466058 rgb/1341840091.466058.png 1341840091.466080 depth/1341840091.466080.png
1341840091.498556 rgb/1341840091.498556.png 1341840091.498572 depth/1341840091.498572.png
1341840091.530216 rgb/1341840091.530216.png 1341840091.530229 depth/1341840091.530229.png
1341840091.566121 rgb/1341840091.566121.png 1341840091.566238 depth/1341840091.566238.png
1341840091.598358 rgb/1341840091.598358.png 1341840091.598372 depth/1341840091.598372.png
1341840091.634045 rgb/1341840091.634045.png 1341840091.634059 depth/1341840091.634059.png
1341840091.666147 rgb/1341840091.666147.png 1341840091.666167 depth/1341840091.666167.png
1341840091.698112 rgb/1341840091.698112.png 1341840091.699242 depth/1341840091.699242.png
1341840091.734036 rgb/1341840091.734036.png 1341840091.734051 depth/1341840091.734051.png
1341840091.766000 rgb/1341840091.766000.png 1341840091.766015 depth/1341840091.766015.png
1341840091.801977 rgb/1341840091.801977.png 1341840091.801995 depth/1341840091.801995.png
1341840091.834055 rgb/1341840091.834055.png 1341840091.834069 depth/1341840091.834069.png
1341840091.866167 rgb/1341840091.866167.png 1341840091.866182 depth/1341840091.866182.png
1341840091.902016 rgb/1341840091.902016.png 1341840091.902032 depth/1341840091.902032.png
1341840091.933960 rgb/1341840091.933960.png 1341840091.933976 depth/1341840091.933976.png
1341840091.965991 rgb/1341840091.965991.png 1341840091.966052 depth/1341840091.966052.png
1341840092.002090 rgb/1341840092.002090.png 1341840092.002101 depth/1341840092.002101.png
1341840092.034037 rgb/1341840092.034037.png 1341840092.034052 depth/1341840092.034052.png
1341840092.069963 rgb/1341840092.069963.png 1341840092.069974 depth/1341840092.069974.png
1341840092.102060 rgb/1341840092.102060.png 1341840092.102072 depth/1341840092.102072.png
1341840092.133897 rgb/1341840092.133897.png 1341840092.133911 depth/1341840092.133911.png
1341840092.169986 rgb/1341840092.169986.png 1341840092.169998 depth/1341840092.169998.png
1341840092.202031 rgb/1341840092.202031.png 1341840092.202054 depth/1341840092.202054.png
1341840092.234005 rgb/1341840092.234005.png 1341840092.234021 depth/1341840092.234021.png
1341840092.269975 rgb/1341840092.269975.png 1341840092.269985 depth/1341840092.269985.png
1341840092.302076 rgb/1341840092.302076.png 1341840092.302121 depth/1341840092.302121.png
1341840092.338133 rgb/1341840092.338133.png 1341840092.338192 depth/1341840092.338192.png
1341840092.370097 rgb/1341840092.370097.png 1341840092.370114 depth/1341840092.370114.png
1341840092.401970 rgb/1341840092.401970.png 1341840092.402177 depth/1341840092.402177.png
1341840092.437934 rgb/1341840092.437934.png 1341840092.437951 depth/1341840092.437951.png
1341840092.469968 rgb/1341840092.469968.png 1341840092.469979 depth/1341840092.469979.png
1341840092.501965 rgb/1341840092.501965.png 1341840092.501977 depth/1341840092.501977.png
1341840092.538065 rgb/1341840092.538065.png 1341840092.538074 depth/1341840092.538074.png
1341840092.570615 rgb/1341840092.570615.png 1341840092.570719 depth/1341840092.570719.png
1341840092.606041 rgb/1341840092.606041.png 1341840092.606052 depth/1341840092.606052.png
1341840092.638035 rgb/1341840092.638035.png 1341840092.638059 depth/1341840092.638059.png
1341840092.670218 rgb/1341840092.670218.png 1341840092.671634 depth/1341840092.671634.png
1341840092.707285 rgb/1341840092.707285.png 1341840092.707855 depth/1341840092.707855.png
1341840092.738009 rgb/1341840092.738009.png 1341840092.738587 depth/1341840092.738587.png
1341840092.774020 rgb/1341840092.774020.png 1341840092.774028 depth/1341840092.774028.png
1341840092.806419 rgb/1341840092.806419.png 1341840092.806436 depth/1341840092.806436.png
1341840092.838581 rgb/1341840092.838581.png 1341840092.838596 depth/1341840092.838596.png
1341840092.874105 rgb/1341840092.874105.png 1341840092.874114 depth/1341840092.874114.png
1341840092.906168 rgb/1341840092.906168.png 1341840092.906186 depth/1341840092.906186.png
1341840092.938208 rgb/1341840092.938208.png 1341840092.938231 depth/1341840092.938231.png
1341840092.974015 rgb/1341840092.974015.png 1341840092.974036 depth/1341840092.974036.png
1341840093.005964 rgb/1341840093.005964.png 1341840093.005985 depth/1341840093.005985.png
1341840093.041963 rgb/1341840093.041963.png 1341840093.041974 depth/1341840093.041974.png
1341840093.074068 rgb/1341840093.074068.png 1341840093.074683 depth/1341840093.074683.png
1341840093.105999 rgb/1341840093.105999.png 1341840093.106011 depth/1341840093.106011.png
1341840093.142176 rgb/1341840093.142176.png 1341840093.142189 depth/1341840093.142189.png
1341840093.174102 rgb/1341840093.174102.png 1341840093.174777 depth/1341840093.174777.png
1341840093.205980 rgb/1341840093.205980.png 1341840093.205988 depth/1341840093.205988.png
1341840093.241963 rgb/1341840093.241963.png 1341840093.241988 depth/1341840093.241988.png
1341840093.274028 rgb/1341840093.274028.png 1341840093.274036 depth/1341840093.274036.png
1341840093.310076 rgb/1341840093.310076.png 1341840093.310093 depth/1341840093.310093.png
1341840093.342068 rgb/1341840093.342068.png 1341840093.342081 depth/1341840093.342081.png
1341840093.374183 rgb/1341840093.374183.png 1341840093.374197 depth/1341840093.374197.png
1341840093.410028 rgb/1341840093.410028.png 1341840093.410042 depth/1341840093.410042.png
1341840093.442035 rgb/1341840093.442035.png 1341840093.442046 depth/1341840093.442046.png
1341840093.474124 rgb/1341840093.474124.png 1341840093.474136 depth/1341840093.474136.png
1341840093.510180 rgb/1341840093.510180.png 1341840093.510242 depth/1341840093.510242.png
1341840093.542037 rgb/1341840093.542037.png 1341840093.542052 depth/1341840093.542052.png
1341840093.578056 rgb/1341840093.578056.png 1341840093.578126 depth/1341840093.578126.png
1341840093.609967 rgb/1341840093.609967.png 1341840093.610020 depth/1341840093.610020.png
1341840093.642118 rgb/1341840093.642118.png 1341840093.642128 depth/1341840093.642128.png
1341840093.678248 rgb/1341840093.678248.png 1341840093.678313 depth/1341840093.678313.png
1341840093.709940 rgb/1341840093.709940.png 1341840093.709969 depth/1341840093.709969.png
1341840093.742135 rgb/1341840093.742135.png 1341840093.742153 depth/1341840093.742153.png
1341840093.778128 rgb/1341840093.778128.png 1341840093.778148 depth/1341840093.778148.png
1341840093.810107 rgb/1341840093.810107.png 1341840093.810127 depth/1341840093.810127.png
1341840093.846050 rgb/1341840093.846050.png 1341840093.846072 depth/1341840093.846072.png
1341840093.910211 rgb/1341840093.910211.png 1341840093.910224 depth/1341840093.910224.png
1341840093.946162 rgb/1341840093.946162.png 1341840093.946171 depth/1341840093.946171.png
1341840093.978106 rgb/1341840093.978106.png 1341840093.978157 depth/1341840093.978157.png
1341840094.014200 rgb/1341840094.014200.png 1341840094.014218 depth/1341840094.014218.png
1341840094.045955 rgb/1341840094.045955.png 1341840094.045969 depth/1341840094.045969.png
1341840094.078220 rgb/1341840094.078220.png 1341840094.078296 depth/1341840094.078296.png
1341840094.114075 rgb/1341840094.114075.png 1341840094.114089 depth/1341840094.114089.png
1341840094.145961 rgb/1341840094.145961.png 1341840094.146013 depth/1341840094.146013.png
1341840094.177988 rgb/1341840094.177988.png 1341840094.178004 depth/1341840094.178004.png
1341840094.213995 rgb/1341840094.213995.png 1341840094.214006 depth/1341840094.214006.png
1341840094.245995 rgb/1341840094.245995.png 1341840094.246029 depth/1341840094.246029.png
1341840094.282114 rgb/1341840094.282114.png 1341840094.282127 depth/1341840094.282127.png
1341840094.314003 rgb/1341840094.314003.png 1341840094.314011 depth/1341840094.314011.png
1341840094.346025 rgb/1341840094.346025.png 1341840094.346053 depth/1341840094.346053.png
1341840094.382137 rgb/1341840094.382137.png 1341840094.382153 depth/1341840094.382153.png
1341840094.414276 rgb/1341840094.414276.png 1341840094.414305 depth/1341840094.414305.png
1341840094.446017 rgb/1341840094.446017.png 1341840094.446030 depth/1341840094.446030.png
1341840094.481962 rgb/1341840094.481962.png 1341840094.482013 depth/1341840094.482013.png
1341840094.514223 rgb/1341840094.514223.png 1341840094.514266 depth/1341840094.514266.png
1341840094.550073 rgb/1341840094.550073.png 1341840094.550086 depth/1341840094.550086.png
1341840094.582272 rgb/1341840094.582272.png 1341840094.583134 depth/1341840094.583134.png
1341840094.615563 rgb/1341840094.615563.png 1341840094.615579 depth/1341840094.615579.png
1341840094.682271 rgb/1341840094.682271.png 1341840094.682299 depth/1341840094.682299.png
1341840094.715723 rgb/1341840094.715723.png 1341840094.715741 depth/1341840094.715741.png
1341840094.752733 rgb/1341840094.752733.png 1341840094.753976 depth/1341840094.753976.png
1341840094.782622 rgb/1341840094.782622.png 1341840094.783242 depth/1341840094.783242.png
1341840094.818366 rgb/1341840094.818366.png 1341840094.818957 depth/1341840094.818957.png
1341840094.850069 rgb/1341840094.850069.png 1341840094.850087 depth/1341840094.850087.png
1341840094.882000 rgb/1341840094.882000.png 1341840094.882748 depth/1341840094.882748.png
1341840094.918054 rgb/1341840094.918054.png 1341840094.918073 depth/1341840094.918073.png
1341840094.949944 rgb/1341840094.949944.png 1341840094.950025 depth/1341840094.950025.png
1341840094.985953 rgb/1341840094.985953.png 1341840094.985975 depth/1341840094.985975.png
1341840095.017986 rgb/1341840095.017986.png 1341840095.018094 depth/1341840095.018094.png
1341840095.050029 rgb/1341840095.050029.png 1341840095.050044 depth/1341840095.050044.png
1341840095.086058 rgb/1341840095.086058.png 1341840095.086070 depth/1341840095.086070.png
1341840095.118044 rgb/1341840095.118044.png 1341840095.118063 depth/1341840095.118063.png
1341840095.150110 rgb/1341840095.150110.png 1341840095.150130 depth/1341840095.150130.png
1341840095.186169 rgb/1341840095.186169.png 1341840095.186180 depth/1341840095.186180.png
1341840095.218041 rgb/1341840095.218041.png 1341840095.218053 depth/1341840095.218053.png
1341840095.254017 rgb/1341840095.254017.png 1341840095.254034 depth/1341840095.254034.png
1341840095.285981 rgb/1341840095.285981.png 1341840095.285993 depth/1341840095.285993.png
1341840095.318140 rgb/1341840095.318140.png 1341840095.318156 depth/1341840095.318156.png
1341840095.354079 rgb/1341840095.354079.png 1341840095.354097 depth/1341840095.354097.png
1341840095.385974 rgb/1341840095.385974.png 1341840095.385988 depth/1341840095.385988.png
1341840095.417958 rgb/1341840095.417958.png 1341840095.417990 depth/1341840095.417990.png
1341840095.454028 rgb/1341840095.454028.png 1341840095.454044 depth/1341840095.454044.png
1341840095.486008 rgb/1341840095.486008.png 1341840095.486027 depth/1341840095.486027.png
1341840095.522111 rgb/1341840095.522111.png 1341840095.522143 depth/1341840095.522143.png
1341840095.554366 rgb/1341840095.554366.png 1341840095.554376 depth/1341840095.554376.png
1341840095.586122 rgb/1341840095.586122.png 1341840095.586148 depth/1341840095.586148.png
1341840095.621980 rgb/1341840095.621980.png 1341840095.621993 depth/1341840095.621993.png
1341840095.653945 rgb/1341840095.653945.png 1341840095.653994 depth/1341840095.653994.png
1341840095.686009 rgb/1341840095.686009.png 1341840095.686021 depth/1341840095.686021.png
1341840095.721971 rgb/1341840095.721971.png 1341840095.721997 depth/1341840095.721997.png
1341840095.753967 rgb/1341840095.753967.png 1341840095.753976 depth/1341840095.753976.png
1341840095.789981 rgb/1341840095.789981.png 1341840095.789996 depth/1341840095.789996.png
1341840095.821991 rgb/1341840095.821991.png 1341840095.822005 depth/1341840095.822005.png
1341840095.853993 rgb/1341840095.853993.png 1341840095.854012 depth/1341840095.854012.png
1341840095.890167 rgb/1341840095.890167.png 1341840095.890184 depth/1341840095.890184.png
1341840095.922043 rgb/1341840095.922043.png 1341840095.922065 depth/1341840095.922065.png
1341840095.953986 rgb/1341840095.953986.png 1341840095.954011 depth/1341840095.954011.png
1341840095.990074 rgb/1341840095.990074.png 1341840095.990091 depth/1341840095.990091.png
1341840096.022067 rgb/1341840096.022067.png 1341840096.022106 depth/1341840096.022106.png
1341840096.058118 rgb/1341840096.058118.png 1341840096.058155 depth/1341840096.058155.png
1341840096.090098 rgb/1341840096.090098.png 1341840096.090125 depth/1341840096.090125.png
1341840096.122246 rgb/1341840096.122246.png 1341840096.122266 depth/1341840096.122266.png
1341840096.157960 rgb/1341840096.157960.png 1341840096.157987 depth/1341840096.157987.png
1341840096.190067 rgb/1341840096.190067.png 1341840096.190087 depth/1341840096.190087.png
1341840096.226024 rgb/1341840096.226024.png 1341840096.226045 depth/1341840096.226045.png
1341840096.258026 rgb/1341840096.258026.png 1341840096.258050 depth/1341840096.258050.png
1341840096.290017 rgb/1341840096.290017.png 1341840096.290048 depth/1341840096.290048.png
1341840096.326010 rgb/1341840096.326010.png 1341840096.326031 depth/1341840096.326031.png
1341840096.365135 rgb/1341840096.365135.png 1341840096.365180 depth/1341840096.365180.png
1341840096.426063 rgb/1341840096.426063.png 1341840096.426074 depth/1341840096.426074.png
1341840096.458130 rgb/1341840096.458130.png 1341840096.458145 depth/1341840096.458145.png
1341840096.493964 rgb/1341840096.493964.png 1341840096.493977 depth/1341840096.493977.png
1341840096.557989 rgb/1341840096.557989.png 1341840096.558022 depth/1341840096.558022.png
1341840096.594051 rgb/1341840096.594051.png 1341840096.594066 depth/1341840096.594066.png
1341840096.625905 rgb/1341840096.625905.png 1341840096.625939 depth/1341840096.625939.png
1341840096.658100 rgb/1341840096.658100.png 1341840096.658123 depth/1341840096.658123.png
1341840096.694102 rgb/1341840096.694102.png 1341840096.694138 depth/1341840096.694138.png
1341840096.726051 rgb/1341840096.726051.png 1341840096.726064 depth/1341840096.726064.png
1341840096.762093 rgb/1341840096.762093.png 1341840096.762101 depth/1341840096.762101.png
1341840096.793991 rgb/1341840096.793991.png 1341840096.794009 depth/1341840096.794009.png
1341840096.825964 rgb/1341840096.825964.png 1341840096.825990 depth/1341840096.825990.png
1341840096.862107 rgb/1341840096.862107.png 1341840096.862123 depth/1341840096.862123.png
1341840096.893996 rgb/1341840096.893996.png 1341840096.894017 depth/1341840096.894017.png
1341840096.926123 rgb/1341840096.926123.png 1341840096.926145 depth/1341840096.926145.png
1341840096.962109 rgb/1341840096.962109.png 1341840096.962146 depth/1341840096.962146.png
1341840096.994381 rgb/1341840096.994381.png 1341840096.994428 depth/1341840096.994428.png
1341840097.030022 rgb/1341840097.030022.png 1341840097.030045 depth/1341840097.030045.png
1341840097.062043 rgb/1341840097.062043.png 1341840097.062063 depth/1341840097.062063.png
1341840097.094113 rgb/1341840097.094113.png 1341840097.094124 depth/1341840097.094124.png
1341840097.130197 rgb/1341840097.130197.png 1341840097.130835 depth/1341840097.130835.png
1341840097.162122 rgb/1341840097.162122.png 1341840097.162137 depth/1341840097.162137.png
1341840097.198273 rgb/1341840097.198273.png 1341840097.198292 depth/1341840097.198292.png
1341840097.230163 rgb/1341840097.230163.png 1341840097.230185 depth/1341840097.230185.png
1341840097.262128 rgb/1341840097.262128.png 1341840097.262646 depth/1341840097.262646.png
1341840097.298060 rgb/1341840097.298060.png 1341840097.298081 depth/1341840097.298081.png
1341840097.330044 rgb/1341840097.330044.png 1341840097.330081 depth/1341840097.330081.png
1341840097.398069 rgb/1341840097.398069.png 1341840097.398078 depth/1341840097.398078.png
1341840097.430211 rgb/1341840097.430211.png 1341840097.430228 depth/1341840097.430228.png
1341840097.465939 rgb/1341840097.465939.png 1341840097.466443 depth/1341840097.466443.png
1341840097.498027 rgb/1341840097.498027.png 1341840097.498071 depth/1341840097.498071.png
1341840097.530195 rgb/1341840097.530195.png 1341840097.530217 depth/1341840097.530217.png
1341840097.566099 rgb/1341840097.566099.png 1341840097.566510 depth/1341840097.566510.png
1341840097.598108 rgb/1341840097.598108.png 1341840097.598143 depth/1341840097.598143.png
1341840097.630355 rgb/1341840097.630355.png 1341840097.630382 depth/1341840097.630382.png
1341840097.665927 rgb/1341840097.665927.png 1341840097.665944 depth/1341840097.665944.png
1341840097.698115 rgb/1341840097.698115.png 1341840097.698126 depth/1341840097.698126.png
1341840097.734100 rgb/1341840097.734100.png 1341840097.734130 depth/1341840097.734130.png
1341840097.766062 rgb/1341840097.766062.png 1341840097.766100 depth/1341840097.766100.png
1341840097.799766 rgb/1341840097.799766.png 1341840097.799793 depth/1341840097.799793.png
1341840097.834458 rgb/1341840097.834458.png 1341840097.834483 depth/1341840097.834483.png
1341840097.866563 rgb/1341840097.866563.png 1341840097.866577 depth/1341840097.866577.png
1341840097.897960 rgb/1341840097.897960.png 1341840097.897978 depth/1341840097.897978.png
1341840097.933958 rgb/1341840097.933958.png 1341840097.933978 depth/1341840097.933978.png
1341840097.965962 rgb/1341840097.965962.png 1341840097.965986 depth/1341840097.965986.png
1341840098.002067 rgb/1341840098.002067.png 1341840098.002087 depth/1341840098.002087.png
1341840098.033966 rgb/1341840098.033966.png 1341840098.033986 depth/1341840098.033986.png
1341840098.066017 rgb/1341840098.066017.png 1341840098.066026 depth/1341840098.066026.png
1341840098.102112 rgb/1341840098.102112.png 1341840098.102122 depth/1341840098.102122.png
1341840098.133988 rgb/1341840098.133988.png 1341840098.134056 depth/1341840098.134056.png
1341840098.166085 rgb/1341840098.166085.png 1341840098.166110 depth/1341840098.166110.png
1341840098.202060 rgb/1341840098.202060.png 1341840098.202074 depth/1341840098.202074.png
1341840098.233997 rgb/1341840098.233997.png 1341840098.234004 depth/1341840098.234004.png
1341840098.269976 rgb/1341840098.269976.png 1341840098.269992 depth/1341840098.269992.png
1341840098.302041 rgb/1341840098.302041.png 1341840098.302103 depth/1341840098.302103.png
1341840098.333999 rgb/1341840098.333999.png 1341840098.334010 depth/1341840098.334010.png
1341840098.369946 rgb/1341840098.369946.png 1341840098.369957 depth/1341840098.369957.png
1341840098.401992 rgb/1341840098.401992.png 1341840098.402007 depth/1341840098.402007.png
1341840098.438538 rgb/1341840098.438538.png 1341840098.438553 depth/1341840098.438553.png
1341840098.470049 rgb/1341840098.470049.png 1341840098.470063 depth/1341840098.470063.png
1341840098.502216 rgb/1341840098.502216.png 1341840098.502743 depth/1341840098.502743.png
1341840098.538046 rgb/1341840098.538046.png 1341840098.538321 depth/1341840098.538321.png
1341840098.569979 rgb/1341840098.569979.png 1341840098.569992 depth/1341840098.569992.png
1341840098.601991 rgb/1341840098.601991.png 1341840098.602061 depth/1341840098.602061.png
1341840098.638011 rgb/1341840098.638011.png 1341840098.638022 depth/1341840098.638022.png
1341840098.669979 rgb/1341840098.669979.png 1341840098.670000 depth/1341840098.670000.png
1341840098.706035 rgb/1341840098.706035.png 1341840098.706062 depth/1341840098.706062.png
1341840098.737998 rgb/1341840098.737998.png 1341840098.738008 depth/1341840098.738008.png
1341840098.770012 rgb/1341840098.770012.png 1341840098.770061 depth/1341840098.770061.png
1341840098.806004 rgb/1341840098.806004.png 1341840098.806043 depth/1341840098.806043.png
1341840098.838054 rgb/1341840098.838054.png 1341840098.838574 depth/1341840098.838574.png
1341840098.870018 rgb/1341840098.870018.png 1341840098.870060 depth/1341840098.870060.png
1341840098.905941 rgb/1341840098.905941.png 1341840098.905985 depth/1341840098.905985.png
1341840098.937995 rgb/1341840098.937995.png 1341840098.938021 depth/1341840098.938021.png
1341840098.974247 rgb/1341840098.974247.png 1341840098.974264 depth/1341840098.974264.png
1341840099.005991 rgb/1341840099.005991.png 1341840099.006034 depth/1341840099.006034.png
1341840099.038009 rgb/1341840099.038009.png 1341840099.038033 depth/1341840099.038033.png
1341840099.074065 rgb/1341840099.074065.png 1341840099.074074 depth/1341840099.074074.png
1341840099.106137 rgb/1341840099.106137.png 1341840099.106197 depth/1341840099.106197.png
1341840099.138052 rgb/1341840099.138052.png 1341840099.138083 depth/1341840099.138083.png
1341840099.174134 rgb/1341840099.174134.png 1341840099.174147 depth/1341840099.174147.png
1341840099.206089 rgb/1341840099.206089.png 1341840099.206106 depth/1341840099.206106.png
1341840099.242010 rgb/1341840099.242010.png 1341840099.242026 depth/1341840099.242026.png
1341840099.274189 rgb/1341840099.274189.png 1341840099.274198 depth/1341840099.274198.png
1341840099.313480 rgb/1341840099.313480.png 1341840099.313529 depth/1341840099.313529.png
1341840099.374131 rgb/1341840099.374131.png 1341840099.374173 depth/1341840099.374173.png
1341840099.410022 rgb/1341840099.410022.png 1341840099.410043 depth/1341840099.410043.png
1341840099.441968 rgb/1341840099.441968.png 1341840099.441995 depth/1341840099.441995.png
1341840099.474148 rgb/1341840099.474148.png 1341840099.474161 depth/1341840099.474161.png
1341840099.509932 rgb/1341840099.509932.png 1341840099.509953 depth/1341840099.509953.png
1341840099.542031 rgb/1341840099.542031.png 1341840099.542044 depth/1341840099.542044.png
1341840099.610204 rgb/1341840099.610204.png 1341840099.610263 depth/1341840099.610263.png
1341840099.641985 rgb/1341840099.641985.png 1341840099.641994 depth/1341840099.641994.png
1341840099.678015 rgb/1341840099.678015.png 1341840099.678114 depth/1341840099.678114.png
1341840099.710201 rgb/1341840099.710201.png 1341840099.710816 depth/1341840099.710816.png
1341840099.742027 rgb/1341840099.742027.png 1341840099.742046 depth/1341840099.742046.png
1341840099.777936 rgb/1341840099.777936.png 1341840099.777948 depth/1341840099.777948.png
1341840099.810002 rgb/1341840099.810002.png 1341840099.810011 depth/1341840099.810011.png
1341840099.842110 rgb/1341840099.842110.png 1341840099.842724 depth/1341840099.842724.png
1341840099.878109 rgb/1341840099.878109.png 1341840099.878695 depth/1341840099.878695.png
1341840099.909941 rgb/1341840099.909941.png 1341840099.909983 depth/1341840099.909983.png
1341840099.946242 rgb/1341840099.946242.png 1341840099.946260 depth/1341840099.946260.png
1341840099.977991 rgb/1341840099.977991.png 1341840099.978006 depth/1341840099.978006.png
1341840100.010063 rgb/1341840100.010063.png 1341840100.010072 depth/1341840100.010072.png
1341840100.046198 rgb/1341840100.046198.png 1341840100.046243 depth/1341840100.046243.png
1341840100.077944 rgb/1341840100.077944.png 1341840100.077981 depth/1341840100.077981.png
1341840100.110081 rgb/1341840100.110081.png 1341840100.110101 depth/1341840100.110101.png
1341840100.146035 rgb/1341840100.146035.png 1341840100.146177 depth/1341840100.146177.png
1341840100.178200 rgb/1341840100.178200.png 1341840100.178222 depth/1341840100.178222.png
1341840100.215238 rgb/1341840100.215238.png 1341840100.215353 depth/1341840100.215353.png
1341840100.278200 rgb/1341840100.278200.png 1341840100.278206 depth/1341840100.278206.png
1341840100.314468 rgb/1341840100.314468.png 1341840100.314511 depth/1341840100.314511.png
1341840100.345946 rgb/1341840100.345946.png 1341840100.346221 depth/1341840100.346221.png
1341840100.378127 rgb/1341840100.378127.png 1341840100.378139 depth/1341840100.378139.png
1341840100.414163 rgb/1341840100.414163.png 1341840100.414176 depth/1341840100.414176.png
1341840100.446292 rgb/1341840100.446292.png 1341840100.446318 depth/1341840100.446318.png
1341840100.482170 rgb/1341840100.482170.png 1341840100.482352 depth/1341840100.482352.png
1341840100.513929 rgb/1341840100.513929.png 1341840100.513978 depth/1341840100.513978.png
1341840100.546213 rgb/1341840100.546213.png 1341840100.546229 depth/1341840100.546229.png
1341840100.582002 rgb/1341840100.582002.png 1341840100.582028 depth/1341840100.582028.png
1341840100.614097 rgb/1341840100.614097.png 1341840100.614147 depth/1341840100.614147.png
1341840100.649997 rgb/1341840100.649997.png 1341840100.650017 depth/1341840100.650017.png
1341840100.682252 rgb/1341840100.682252.png 1341840100.682272 depth/1341840100.682272.png
1341840100.714000 rgb/1341840100.714000.png 1341840100.714013 depth/1341840100.714013.png
1341840100.749993 rgb/1341840100.749993.png 1341840100.750006 depth/1341840100.750006.png
1341840100.782007 rgb/1341840100.782007.png 1341840100.782031 depth/1341840100.782031.png
1341840100.814025 rgb/1341840100.814025.png 1341840100.814063 depth/1341840100.814063.png
1341840100.850129 rgb/1341840100.850129.png 1341840100.850154 depth/1341840100.850154.png
1341840100.881983 rgb/1341840100.881983.png 1341840100.882003 depth/1341840100.882003.png
1341840100.918146 rgb/1341840100.918146.png 1341840100.918223 depth/1341840100.918223.png
1341840100.950032 rgb/1341840100.950032.png 1341840100.950043 depth/1341840100.950043.png
1341840100.982020 rgb/1341840100.982020.png 1341840100.982031 depth/1341840100.982031.png
1341840101.018061 rgb/1341840101.018061.png 1341840101.018086 depth/1341840101.018086.png
1341840101.050199 rgb/1341840101.050199.png 1341840101.050306 depth/1341840101.050306.png
1341840101.081947 rgb/1341840101.081947.png 1341840101.081964 depth/1341840101.081964.png
1341840101.118070 rgb/1341840101.118070.png 1341840101.118081 depth/1341840101.118081.png
1341840101.150042 rgb/1341840101.150042.png 1341840101.150065 depth/1341840101.150065.png
1341840101.185930 rgb/1341840101.185930.png 1341840101.185947 depth/1341840101.185947.png
1341840101.218045 rgb/1341840101.218045.png 1341840101.218080 depth/1341840101.218080.png
1341840101.253078 rgb/1341840101.253078.png 1341840101.253148 depth/1341840101.253148.png
1341840101.286158 rgb/1341840101.286158.png 1341840101.286174 depth/1341840101.286174.png
1341840101.318064 rgb/1341840101.318064.png 1341840101.318499 depth/1341840101.318499.png
1341840101.349978 rgb/1341840101.349978.png 1341840101.349991 depth/1341840101.349991.png
1341840101.386236 rgb/1341840101.386236.png 1341840101.386245 depth/1341840101.386245.png
1341840101.418064 rgb/1341840101.418064.png 1341840101.418071 depth/1341840101.418071.png
1341840101.454068 rgb/1341840101.454068.png 1341840101.454096 depth/1341840101.454096.png
1341840101.486162 rgb/1341840101.486162.png 1341840101.486940 depth/1341840101.486940.png
1341840101.518024 rgb/1341840101.518024.png 1341840101.518061 depth/1341840101.518061.png
1341840101.554371 rgb/1341840101.554371.png 1341840101.554434 depth/1341840101.554434.png
1341840101.585933 rgb/1341840101.585933.png 1341840101.585970 depth/1341840101.585970.png
1341840101.621943 rgb/1341840101.621943.png 1341840101.621982 depth/1341840101.621982.png
1341840101.654039 rgb/1341840101.654039.png 1341840101.654056 depth/1341840101.654056.png
1341840101.686008 rgb/1341840101.686008.png 1341840101.686052 depth/1341840101.686052.png
1341840101.721937 rgb/1341840101.721937.png 1341840101.721973 depth/1341840101.721973.png
1341840101.753999 rgb/1341840101.753999.png 1341840101.754035 depth/1341840101.754035.png
1341840101.786021 rgb/1341840101.786021.png 1341840101.786108 depth/1341840101.786108.png
1341840101.821978 rgb/1341840101.821978.png 1341840101.822034 depth/1341840101.822034.png
1341840101.854032 rgb/1341840101.854032.png 1341840101.854052 depth/1341840101.854052.png
1341840101.890071 rgb/1341840101.890071.png 1341840101.890104 depth/1341840101.890104.png
1341840101.921957 rgb/1341840101.921957.png 1341840101.921995 depth/1341840101.921995.png
1341840101.953985 rgb/1341840101.953985.png 1341840101.954051 depth/1341840101.954051.png
1341840101.990056 rgb/1341840101.990056.png 1341840101.990099 depth/1341840101.990099.png
1341840102.022239 rgb/1341840102.022239.png 1341840102.022306 depth/1341840102.022306.png
1341840102.054164 rgb/1341840102.054164.png 1341840102.054198 depth/1341840102.054198.png
1341840102.089965 rgb/1341840102.089965.png 1341840102.090016 depth/1341840102.090016.png
1341840102.122063 rgb/1341840102.122063.png 1341840102.122090 depth/1341840102.122090.png
1341840102.158709 rgb/1341840102.158709.png 1341840102.158245 depth/1341840102.158245.png
1341840102.190046 rgb/1341840102.190046.png 1341840102.190083 depth/1341840102.190083.png
1341840102.221963 rgb/1341840102.221963.png 1341840102.221992 depth/1341840102.221992.png
1341840102.258028 rgb/1341840102.258028.png 1341840102.258040 depth/1341840102.258040.png
1341840102.289992 rgb/1341840102.289992.png 1341840102.290004 depth/1341840102.290004.png
1341840102.322004 rgb/1341840102.322004.png 1341840102.322019 depth/1341840102.322019.png
1341840102.357985 rgb/1341840102.357985.png 1341840102.357993 depth/1341840102.357993.png
1341840102.389994 rgb/1341840102.389994.png 1341840102.390006 depth/1341840102.390006.png
1341840102.426192 rgb/1341840102.426192.png 1341840102.426209 depth/1341840102.426209.png
1341840102.457974 rgb/1341840102.457974.png 1341840102.457985 depth/1341840102.457985.png
1341840102.489909 rgb/1341840102.489909.png 1341840102.489942 depth/1341840102.489942.png
1341840102.525928 rgb/1341840102.525928.png 1341840102.525941 depth/1341840102.525941.png
1341840102.558042 rgb/1341840102.558042.png 1341840102.558064 depth/1341840102.558064.png
1341840102.589964 rgb/1341840102.589964.png 1341840102.589974 depth/1341840102.589974.png
1341840102.625930 rgb/1341840102.625930.png 1341840102.625937 depth/1341840102.625937.png
1341840102.658156 rgb/1341840102.658156.png 1341840102.658198 depth/1341840102.658198.png
1341840102.694450 rgb/1341840102.694450.png 1341840102.694466 depth/1341840102.694466.png
1341840102.725995 rgb/1341840102.725995.png 1341840102.726013 depth/1341840102.726013.png
1341840102.758299 rgb/1341840102.758299.png 1341840102.758320 depth/1341840102.758320.png
1341840102.794279 rgb/1341840102.794279.png 1341840102.794551 depth/1341840102.794551.png
1341840102.826150 rgb/1341840102.826150.png 1341840102.826165 depth/1341840102.826165.png
1341840102.894146 rgb/1341840102.894146.png 1341840102.894163 depth/1341840102.894163.png
1341840102.933073 rgb/1341840102.933073.png 1341840102.933092 depth/1341840102.933092.png
1341840102.969086 rgb/1341840102.969086.png 1341840102.969815 depth/1341840102.969815.png
1341840103.001248 rgb/1341840103.001248.png 1341840103.001933 depth/1341840103.001933.png
1341840103.033319 rgb/1341840103.033319.png 1341840103.033337 depth/1341840103.033337.png
1341840103.068955 rgb/1341840103.068955.png 1341840103.068997 depth/1341840103.068997.png
1341840103.100979 rgb/1341840103.100979.png 1341840103.101450 depth/1341840103.101450.png
1341840103.133214 rgb/1341840103.133214.png 1341840103.133233 depth/1341840103.133233.png
1341840103.169178 rgb/1341840103.169178.png 1341840103.169193 depth/1341840103.169193.png
1341840103.200997 rgb/1341840103.200997.png 1341840103.201030 depth/1341840103.201030.png
1341840103.236975 rgb/1341840103.236975.png 1341840103.237023 depth/1341840103.237023.png
1341840103.269372 rgb/1341840103.269372.png 1341840103.269387 depth/1341840103.269387.png
1341840103.301138 rgb/1341840103.301138.png 1341840103.301150 depth/1341840103.301150.png
1341840103.337120 rgb/1341840103.337120.png 1341840103.337146 depth/1341840103.337146.png
1341840103.369061 rgb/1341840103.369061.png 1341840103.369072 depth/1341840103.369072.png
1341840103.401053 rgb/1341840103.401053.png 1341840103.401068 depth/1341840103.401068.png
1341840103.437062 rgb/1341840103.437062.png 1341840103.437071 depth/1341840103.437071.png
1341840103.469037 rgb/1341840103.469037.png 1341840103.470082 depth/1341840103.470082.png
1341840103.505180 rgb/1341840103.505180.png 1341840103.505189 depth/1341840103.505189.png
1341840103.537086 rgb/1341840103.537086.png 1341840103.537094 depth/1341840103.537094.png
1341840103.569032 rgb/1341840103.569032.png 1341840103.569045 depth/1341840103.569045.png
1341840103.606036 rgb/1341840103.606036.png 1341840103.606046 depth/1341840103.606046.png
1341840103.637674 rgb/1341840103.637674.png 1341840103.637702 depth/1341840103.637702.png
1341840103.669007 rgb/1341840103.669007.png 1341840103.669022 depth/1341840103.669022.png
1341840103.705253 rgb/1341840103.705253.png 1341840103.705277 depth/1341840103.705277.png
1341840103.737091 rgb/1341840103.737091.png 1341840103.737100 depth/1341840103.737100.png
1341840103.769171 rgb/1341840103.769171.png 1341840103.769789 depth/1341840103.769789.png
1341840103.805228 rgb/1341840103.805228.png 1341840103.805244 depth/1341840103.805244.png
1341840103.837157 rgb/1341840103.837157.png 1341840103.837179 depth/1341840103.837179.png
1341840103.873084 rgb/1341840103.873084.png 1341840103.873097 depth/1341840103.873097.png
1341840103.906706 rgb/1341840103.906706.png 1341840103.907164 depth/1341840103.907164.png
1341840103.937494 rgb/1341840103.937494.png 1341840103.937521 depth/1341840103.937521.png
1341840103.973092 rgb/1341840103.973092.png 1341840103.973110 depth/1341840103.973110.png
1341840104.005167 rgb/1341840104.005167.png 1341840104.005190 depth/1341840104.005190.png
1341840104.036982 rgb/1341840104.036982.png 1341840104.037008 depth/1341840104.037008.png
1341840104.073174 rgb/1341840104.073174.png 1341840104.073182 depth/1341840104.073182.png
1341840104.105028 rgb/1341840104.105028.png 1341840104.105060 depth/1341840104.105060.png
1341840104.137083 rgb/1341840104.137083.png 1341840104.137094 depth/1341840104.137094.png
1341840104.173061 rgb/1341840104.173061.png 1341840104.173072 depth/1341840104.173072.png
1341840104.205031 rgb/1341840104.205031.png 1341840104.205111 depth/1341840104.205111.png
1341840104.241049 rgb/1341840104.241049.png 1341840104.241057 depth/1341840104.241057.png
1341840104.273043 rgb/1341840104.273043.png 1341840104.273062 depth/1341840104.273062.png
1341840104.305085 rgb/1341840104.305085.png 1341840104.305899 depth/1341840104.305899.png
1341840104.341064 rgb/1341840104.341064.png 1341840104.341940 depth/1341840104.341940.png
1341840104.372984 rgb/1341840104.372984.png 1341840104.373003 depth/1341840104.373003.png
1341840104.404928 rgb/1341840104.404928.png 1341840104.404948 depth/1341840104.404948.png
1341840104.441139 rgb/1341840104.441139.png 1341840104.441166 depth/1341840104.441166.png
1341840104.472949 rgb/1341840104.472949.png 1341840104.473061 depth/1341840104.473061.png
1341840104.505075 rgb/1341840104.505075.png 1341840104.505136 depth/1341840104.505136.png
1341840104.540989 rgb/1341840104.540989.png 1341840104.540997 depth/1341840104.540997.png
1341840104.572927 rgb/1341840104.572927.png 1341840104.572939 depth/1341840104.572939.png
1341840104.609074 rgb/1341840104.609074.png 1341840104.609100 depth/1341840104.609100.png
1341840104.640948 rgb/1341840104.640948.png 1341840104.640969 depth/1341840104.640969.png
1341840104.673069 rgb/1341840104.673069.png 1341840104.673097 depth/1341840104.673097.png
1341840104.709087 rgb/1341840104.709087.png 1341840104.709109 depth/1341840104.709109.png
1341840104.740940 rgb/1341840104.740940.png 1341840104.740966 depth/1341840104.740966.png
1341840104.777040 rgb/1341840104.777040.png 1341840104.777059 depth/1341840104.777059.png
1341840104.809199 rgb/1341840104.809199.png 1341840104.809227 depth/1341840104.809227.png
1341840104.840918 rgb/1341840104.840918.png 1341840104.840943 depth/1341840104.840943.png
1341840104.877040 rgb/1341840104.877040.png 1341840104.877200 depth/1341840104.877200.png
1341840104.908967 rgb/1341840104.908967.png 1341840104.908983 depth/1341840104.908983.png
1341840104.945200 rgb/1341840104.945200.png 1341840104.945242 depth/1341840104.945242.png
1341840104.976967 rgb/1341840104.976967.png 1341840104.976987 depth/1341840104.976987.png
1341840105.009091 rgb/1341840105.009091.png 1341840105.009102 depth/1341840105.009102.png
1341840105.044912 rgb/1341840105.044912.png 1341840105.044953 depth/1341840105.044953.png
1341840105.076982 rgb/1341840105.076982.png 1341840105.076993 depth/1341840105.076993.png
1341840105.112963 rgb/1341840105.112963.png 1341840105.113438 depth/1341840105.113438.png
1341840105.145078 rgb/1341840105.145078.png 1341840105.145087 depth/1341840105.145087.png
1341840105.176904 rgb/1341840105.176904.png 1341840105.176925 depth/1341840105.176925.png
1341840105.213036 rgb/1341840105.213036.png 1341840105.213052 depth/1341840105.213052.png
1341840105.245160 rgb/1341840105.245160.png 1341840105.245170 depth/1341840105.245170.png
1341840105.281007 rgb/1341840105.281007.png 1341840105.281045 depth/1341840105.281045.png
1341840105.313107 rgb/1341840105.313107.png 1341840105.313132 depth/1341840105.313132.png
1341840105.345000 rgb/1341840105.345000.png 1341840105.345009 depth/1341840105.345009.png
1341840105.381032 rgb/1341840105.381032.png 1341840105.381047 depth/1341840105.381047.png
1341840105.413121 rgb/1341840105.413121.png 1341840105.413147 depth/1341840105.413147.png
1341840105.449115 rgb/1341840105.449115.png 1341840105.449688 depth/1341840105.449688.png
1341840105.481450 rgb/1341840105.481450.png 1341840105.481464 depth/1341840105.481464.png
1341840105.514575 rgb/1341840105.514575.png 1341840105.514584 depth/1341840105.514584.png
1341840105.548981 rgb/1341840105.548981.png 1341840105.548995 depth/1341840105.548995.png
1341840105.581060 rgb/1341840105.581060.png 1341840105.581079 depth/1341840105.581079.png
1341840105.617086 rgb/1341840105.617086.png 1341840105.617109 depth/1341840105.617109.png
1341840105.649066 rgb/1341840105.649066.png 1341840105.649099 depth/1341840105.649099.png
1341840105.681012 rgb/1341840105.681012.png 1341840105.681020 depth/1341840105.681020.png
1341840105.717030 rgb/1341840105.717030.png 1341840105.717826 depth/1341840105.717826.png
1341840105.749001 rgb/1341840105.749001.png 1341840105.749086 depth/1341840105.749086.png
1341840105.785122 rgb/1341840105.785122.png 1341840105.785152 depth/1341840105.785152.png
1341840105.817039 rgb/1341840105.817039.png 1341840105.817054 depth/1341840105.817054.png
1341840105.849027 rgb/1341840105.849027.png 1341840105.849040 depth/1341840105.849040.png
1341840105.885061 rgb/1341840105.885061.png 1341840105.885078 depth/1341840105.885078.png
1341840105.917087 rgb/1341840105.917087.png 1341840105.917154 depth/1341840105.917154.png
1341840105.949293 rgb/1341840105.949293.png 1341840105.950717 depth/1341840105.950717.png
1341840105.985293 rgb/1341840105.985293.png 1341840105.986378 depth/1341840105.986378.png
1341840106.018209 rgb/1341840106.018209.png 1341840106.018243 depth/1341840106.018243.png
1341840106.049368 rgb/1341840106.049368.png 1341840106.049384 depth/1341840106.049384.png
1341840106.086360 rgb/1341840106.086360.png 1341840106.085629 depth/1341840106.085629.png
1341840106.146556 rgb/1341840106.146556.png 1341840106.147575 depth/1341840106.147575.png
1341840106.178238 rgb/1341840106.178238.png 1341840106.179426 depth/1341840106.179426.png
1341840106.210613 rgb/1341840106.210613.png 1341840106.211882 depth/1341840106.211882.png
1341840106.247122 rgb/1341840106.247122.png 1341840106.247283 depth/1341840106.247283.png
1341840106.317396 rgb/1341840106.317396.png 1341840106.319151 depth/1341840106.319151.png
1341840106.378203 rgb/1341840106.378203.png 1341840106.378218 depth/1341840106.378218.png
1341840106.414296 rgb/1341840106.414296.png 1341840106.414976 depth/1341840106.414976.png
1341840106.453839 rgb/1341840106.453839.png 1341840106.454299 depth/1341840106.454299.png
1341840106.486326 rgb/1341840106.486326.png 1341840106.487571 depth/1341840106.487571.png
1341840106.546500 rgb/1341840106.546500.png 1341840106.546514 depth/1341840106.546514.png
1341840106.582042 rgb/1341840106.582042.png 1341840106.582062 depth/1341840106.582062.png
1341840106.614595 rgb/1341840106.614595.png 1341840106.614612 depth/1341840106.614612.png
1341840106.653161 rgb/1341840106.653161.png 1341840106.646162 depth/1341840106.646162.png
1341840106.714118 rgb/1341840106.714118.png 1341840106.714142 depth/1341840106.714142.png
1341840106.746220 rgb/1341840106.746220.png 1341840106.746247 depth/1341840106.746247.png
1341840106.782115 rgb/1341840106.782115.png 1341840106.782124 depth/1341840106.782124.png
1341840106.850141 rgb/1341840106.850141.png 1341840106.850154 depth/1341840106.850154.png
1341840106.882047 rgb/1341840106.882047.png 1341840106.882070 depth/1341840106.882070.png
1341840106.914130 rgb/1341840106.914130.png 1341840106.914158 depth/1341840106.914158.png
1341840106.950035 rgb/1341840106.950035.png 1341840106.950094 depth/1341840106.950094.png
1341840106.982620 rgb/1341840106.982620.png 1341840106.982646 depth/1341840106.982646.png
1341840107.014116 rgb/1341840107.014116.png 1341840107.014127 depth/1341840107.014127.png
1341840107.050043 rgb/1341840107.050043.png 1341840107.050122 depth/1341840107.050122.png
1341840107.082017 rgb/1341840107.082017.png 1341840107.082034 depth/1341840107.082034.png
1341840107.118150 rgb/1341840107.118150.png 1341840107.118166 depth/1341840107.118166.png
1341840107.150055 rgb/1341840107.150055.png 1341840107.150091 depth/1341840107.150091.png
1341840107.182063 rgb/1341840107.182063.png 1341840107.182075 depth/1341840107.182075.png
1341840107.218011 rgb/1341840107.218011.png 1341840107.218027 depth/1341840107.218027.png
1341840107.250000 rgb/1341840107.250000.png 1341840107.250013 depth/1341840107.250013.png
1341840107.285924 rgb/1341840107.285924.png 1341840107.285937 depth/1341840107.285937.png
1341840107.318019 rgb/1341840107.318019.png 1341840107.318611 depth/1341840107.318611.png
1341840107.350008 rgb/1341840107.350008.png 1341840107.350020 depth/1341840107.350020.png
1341840107.386092 rgb/1341840107.386092.png 1341840107.386114 depth/1341840107.386114.png
1341840107.417975 rgb/1341840107.417975.png 1341840107.417982 depth/1341840107.417982.png
1341840107.449982 rgb/1341840107.449982.png 1341840107.449991 depth/1341840107.449991.png
1341840107.486069 rgb/1341840107.486069.png 1341840107.486084 depth/1341840107.486084.png
1341840107.518019 rgb/1341840107.518019.png 1341840107.518034 depth/1341840107.518034.png
1341840107.554169 rgb/1341840107.554169.png 1341840107.554183 depth/1341840107.554183.png
1341840107.586166 rgb/1341840107.586166.png 1341840107.586184 depth/1341840107.586184.png
1341840107.617978 rgb/1341840107.617978.png 1341840107.617986 depth/1341840107.617986.png
1341840107.653971 rgb/1341840107.653971.png 1341840107.653995 depth/1341840107.653995.png
1341840107.686007 rgb/1341840107.686007.png 1341840107.686017 depth/1341840107.686017.png
1341840107.729301 rgb/1341840107.729301.png 1341840107.729356 depth/1341840107.729356.png
1341840107.786076 rgb/1341840107.786076.png 1341840107.786087 depth/1341840107.786087.png
1341840107.821949 rgb/1341840107.821949.png 1341840107.821956 depth/1341840107.821956.png
1341840107.854138 rgb/1341840107.854138.png 1341840107.854153 depth/1341840107.854153.png
1341840107.886102 rgb/1341840107.886102.png 1341840107.886106 depth/1341840107.886106.png
1341840107.922085 rgb/1341840107.922085.png 1341840107.922094 depth/1341840107.922094.png
1341840107.954044 rgb/1341840107.954044.png 1341840107.954056 depth/1341840107.954056.png
1341840107.986084 rgb/1341840107.986084.png 1341840107.986114 depth/1341840107.986114.png
1341840108.022288 rgb/1341840108.022288.png 1341840108.022344 depth/1341840108.022344.png
1341840108.053986 rgb/1341840108.053986.png 1341840108.054035 depth/1341840108.054035.png
1341840108.090178 rgb/1341840108.090178.png 1341840108.090194 depth/1341840108.090194.png
1341840108.121965 rgb/1341840108.121965.png 1341840108.121987 depth/1341840108.121987.png
1341840108.154224 rgb/1341840108.154224.png 1341840108.154238 depth/1341840108.154238.png
1341840108.190019 rgb/1341840108.190019.png 1341840108.190038 depth/1341840108.190038.png
1341840108.261441 rgb/1341840108.261441.png 1341840108.261025 depth/1341840108.261025.png
1341840108.322086 rgb/1341840108.322086.png 1341840108.322125 depth/1341840108.322125.png
1341840108.357889 rgb/1341840108.357889.png 1341840108.358002 depth/1341840108.358002.png
1341840108.390032 rgb/1341840108.390032.png 1341840108.390113 depth/1341840108.390113.png
1341840108.421993 rgb/1341840108.421993.png 1341840108.422033 depth/1341840108.422033.png
1341840108.457962 rgb/1341840108.457962.png 1341840108.458413 depth/1341840108.458413.png
1341840108.490057 rgb/1341840108.490057.png 1341840108.490082 depth/1341840108.490082.png
1341840108.526066 rgb/1341840108.526066.png 1341840108.526639 depth/1341840108.526639.png
1341840108.557923 rgb/1341840108.557923.png 1341840108.558246 depth/1341840108.558246.png
1341840108.590163 rgb/1341840108.590163.png 1341840108.590179 depth/1341840108.590179.png
1341840108.626046 rgb/1341840108.626046.png 1341840108.626062 depth/1341840108.626062.png
1341840108.658238 rgb/1341840108.658238.png 1341840108.658271 depth/1341840108.658271.png
1341840108.690101 rgb/1341840108.690101.png 1341840108.690117 depth/1341840108.690117.png
1341840108.726162 rgb/1341840108.726162.png 1341840108.726181 depth/1341840108.726181.png
1341840108.758020 rgb/1341840108.758020.png 1341840108.758036 depth/1341840108.758036.png
1341840108.794146 rgb/1341840108.794146.png 1341840108.794164 depth/1341840108.794164.png
1341840108.826126 rgb/1341840108.826126.png 1341840108.826190 depth/1341840108.826190.png
1341840108.858063 rgb/1341840108.858063.png 1341840108.858083 depth/1341840108.858083.png
1341840108.894068 rgb/1341840108.894068.png 1341840108.894124 depth/1341840108.894124.png
1341840108.926397 rgb/1341840108.926397.png 1341840108.926413 depth/1341840108.926413.png
1341840108.958169 rgb/1341840108.958169.png 1341840108.958823 depth/1341840108.958823.png
1341840108.994061 rgb/1341840108.994061.png 1341840108.994089 depth/1341840108.994089.png
1341840109.026028 rgb/1341840109.026028.png 1341840109.026041 depth/1341840109.026041.png
1341840109.062055 rgb/1341840109.062055.png 1341840109.062328 depth/1341840109.062328.png
1341840109.094102 rgb/1341840109.094102.png 1341840109.094119 depth/1341840109.094119.png
1341840109.126125 rgb/1341840109.126125.png 1341840109.126711 depth/1341840109.126711.png
1341840109.162091 rgb/1341840109.162091.png 1341840109.162308 depth/1341840109.162308.png
1341840109.194070 rgb/1341840109.194070.png 1341840109.194094 depth/1341840109.194094.png
1341840109.226207 rgb/1341840109.226207.png 1341840109.226255 depth/1341840109.226255.png
1341840109.261949 rgb/1341840109.261949.png 1341840109.261966 depth/1341840109.261966.png
1341840109.294245 rgb/1341840109.294245.png 1341840109.294307 depth/1341840109.294307.png
1341840109.330048 rgb/1341840109.330048.png 1341840109.330064 depth/1341840109.330064.png
1341840109.361934 rgb/1341840109.361934.png 1341840109.362040 depth/1341840109.362040.png
1341840109.394174 rgb/1341840109.394174.png 1341840109.394201 depth/1341840109.394201.png
1341840109.430078 rgb/1341840109.430078.png 1341840109.430157 depth/1341840109.430157.png
1341840109.469199 rgb/1341840109.469199.png 1341840109.462169 depth/1341840109.462169.png
1341840109.530025 rgb/1341840109.530025.png 1341840109.530055 depth/1341840109.530055.png
1341840109.562227 rgb/1341840109.562227.png 1341840109.562279 depth/1341840109.562279.png
1341840109.598096 rgb/1341840109.598096.png 1341840109.598170 depth/1341840109.598170.png
1341840109.630157 rgb/1341840109.630157.png 1341840109.630179 depth/1341840109.630179.png
1341840109.662301 rgb/1341840109.662301.png 1341840109.662969 depth/1341840109.662969.png
1341840109.698028 rgb/1341840109.698028.png 1341840109.698631 depth/1341840109.698631.png
1341840109.730942 rgb/1341840109.730942.png 1341840109.731228 depth/1341840109.731228.png
1341840109.765996 rgb/1341840109.765996.png 1341840109.766007 depth/1341840109.766007.png
1341840109.797984 rgb/1341840109.797984.png 1341840109.798067 depth/1341840109.798067.png
1341840109.830020 rgb/1341840109.830020.png 1341840109.830035 depth/1341840109.830035.png
1341840109.866117 rgb/1341840109.866117.png 1341840109.866161 depth/1341840109.866161.png
1341840109.898432 rgb/1341840109.898432.png 1341840109.898450 depth/1341840109.898450.png
1341840109.930018 rgb/1341840109.930018.png 1341840109.930029 depth/1341840109.930029.png
1341840109.966093 rgb/1341840109.966093.png 1341840109.966125 depth/1341840109.966125.png
1341840109.998090 rgb/1341840109.998090.png 1341840109.998101 depth/1341840109.998101.png
1341840110.033947 rgb/1341840110.033947.png 1341840110.034074 depth/1341840110.034074.png
1341840110.066047 rgb/1341840110.066047.png 1341840110.066138 depth/1341840110.066138.png
1341840110.097995 rgb/1341840110.097995.png 1341840110.098013 depth/1341840110.098013.png
1341840110.134023 rgb/1341840110.134023.png 1341840110.134041 depth/1341840110.134041.png
1341840110.166206 rgb/1341840110.166206.png 1341840110.166222 depth/1341840110.166222.png
1341840110.198574 rgb/1341840110.198574.png 1341840110.198590 depth/1341840110.198590.png
1341840110.234162 rgb/1341840110.234162.png 1341840110.234667 depth/1341840110.234667.png
1341840110.266480 rgb/1341840110.266480.png 1341840110.266678 depth/1341840110.266678.png
1341840110.302180 rgb/1341840110.302180.png 1341840110.302244 depth/1341840110.302244.png
1341840110.334151 rgb/1341840110.334151.png 1341840110.334615 depth/1341840110.334615.png
1341840110.366041 rgb/1341840110.366041.png 1341840110.366053 depth/1341840110.366053.png
1341840110.402014 rgb/1341840110.402014.png 1341840110.402031 depth/1341840110.402031.png
1341840110.470485 rgb/1341840110.470485.png 1341840110.472693 depth/1341840110.472693.png
1341840110.502611 rgb/1341840110.502611.png 1341840110.503531 depth/1341840110.503531.png
1341840110.534716 rgb/1341840110.534716.png 1341840110.536123 depth/1341840110.536123.png
1341840110.570160 rgb/1341840110.570160.png 1341840110.570919 depth/1341840110.570919.png
1341840110.602152 rgb/1341840110.602152.png 1341840110.602365 depth/1341840110.602365.png
1341840110.634164 rgb/1341840110.634164.png 1341840110.634751 depth/1341840110.634751.png
1341840110.670463 rgb/1341840110.670463.png 1341840110.670637 depth/1341840110.670637.png
1341840110.702156 rgb/1341840110.702156.png 1341840110.702179 depth/1341840110.702179.png
1341840110.770055 rgb/1341840110.770055.png 1341840110.770092 depth/1341840110.770092.png
1341840110.802298 rgb/1341840110.802298.png 1341840110.802309 depth/1341840110.802309.png
1341840110.838159 rgb/1341840110.838159.png 1341840110.838176 depth/1341840110.838176.png
1341840110.870149 rgb/1341840110.870149.png 1341840110.870187 depth/1341840110.870187.png
1341840110.902063 rgb/1341840110.902063.png 1341840110.902118 depth/1341840110.902118.png
1341840110.938225 rgb/1341840110.938225.png 1341840110.938260 depth/1341840110.938260.png
1341840110.970039 rgb/1341840110.970039.png 1341840110.970062 depth/1341840110.970062.png
1341840111.005980 rgb/1341840111.005980.png 1341840111.006001 depth/1341840111.006001.png
1341840111.038080 rgb/1341840111.038080.png 1341840111.038096 depth/1341840111.038096.png
1341840111.070094 rgb/1341840111.070094.png 1341840111.070109 depth/1341840111.070109.png
1341840111.106101 rgb/1341840111.106101.png 1341840111.106139 depth/1341840111.106139.png
1341840111.138254 rgb/1341840111.138254.png 1341840111.138295 depth/1341840111.138295.png
1341840111.170017 rgb/1341840111.170017.png 1341840111.170029 depth/1341840111.170029.png
1341840111.206027 rgb/1341840111.206027.png 1341840111.206039 depth/1341840111.206039.png
1341840111.238002 rgb/1341840111.238002.png 1341840111.238557 depth/1341840111.238557.png
1341840111.273886 rgb/1341840111.273886.png 1341840111.273894 depth/1341840111.273894.png
1341840111.306061 rgb/1341840111.306061.png 1341840111.306112 depth/1341840111.306112.png
1341840111.338594 rgb/1341840111.338594.png 1341840111.338609 depth/1341840111.338609.png
1341840111.374364 rgb/1341840111.374364.png 1341840111.374382 depth/1341840111.374382.png
1341840111.406608 rgb/1341840111.406608.png 1341840111.407733 depth/1341840111.407733.png
1341840111.438543 rgb/1341840111.438543.png 1341840111.439296 depth/1341840111.439296.png
1341840111.474308 rgb/1341840111.474308.png 1341840111.474993 depth/1341840111.474993.png
1341840111.506766 rgb/1341840111.506766.png 1341840111.507751 depth/1341840111.507751.png
1341840111.542350 rgb/1341840111.542350.png 1341840111.542391 depth/1341840111.542391.png
1341840111.574318 rgb/1341840111.574318.png 1341840111.574347 depth/1341840111.574347.png
1341840111.613190 rgb/1341840111.613190.png 1341840111.613256 depth/1341840111.613256.png
1341840111.674414 rgb/1341840111.674414.png 1341840111.674437 depth/1341840111.674437.png
1341840111.709993 rgb/1341840111.709993.png 1341840111.710021 depth/1341840111.710021.png
1341840111.742130 rgb/1341840111.742130.png 1341840111.742144 depth/1341840111.742144.png
1341840111.773977 rgb/1341840111.773977.png 1341840111.773991 depth/1341840111.773991.png
1341840111.810090 rgb/1341840111.810090.png 1341840111.810108 depth/1341840111.810108.png
1341840111.842092 rgb/1341840111.842092.png 1341840111.842134 depth/1341840111.842134.png
1341840111.873912 rgb/1341840111.873912.png 1341840111.873921 depth/1341840111.873921.png
1341840111.910077 rgb/1341840111.910077.png 1341840111.910090 depth/1341840111.910090.png
1341840111.942341 rgb/1341840111.942341.png 1341840111.942369 depth/1341840111.942369.png
1341840111.978065 rgb/1341840111.978065.png 1341840111.978106 depth/1341840111.978106.png
1341840112.010079 rgb/1341840112.010079.png 1341840112.010095 depth/1341840112.010095.png
1341840112.042150 rgb/1341840112.042150.png 1341840112.042218 depth/1341840112.042218.png
1341840112.078049 rgb/1341840112.078049.png 1341840112.078058 depth/1341840112.078058.png
1341840112.110041 rgb/1341840112.110041.png 1341840112.110157 depth/1341840112.110157.png
1341840112.142067 rgb/1341840112.142067.png 1341840112.142076 depth/1341840112.142076.png
1341840112.178152 rgb/1341840112.178152.png 1341840112.178164 depth/1341840112.178164.png
1341840112.210048 rgb/1341840112.210048.png 1341840112.210086 depth/1341840112.210086.png
1341840112.246294 rgb/1341840112.246294.png 1341840112.246301 depth/1341840112.246301.png
1341840112.277978 rgb/1341840112.277978.png 1341840112.278021 depth/1341840112.278021.png
1341840112.309992 rgb/1341840112.309992.png 1341840112.310053 depth/1341840112.310053.png
1341840112.346126 rgb/1341840112.346126.png 1341840112.346171 depth/1341840112.346171.png
1341840112.378084 rgb/1341840112.378084.png 1341840112.378130 depth/1341840112.378130.png
1341840112.410156 rgb/1341840112.410156.png 1341840112.410164 depth/1341840112.410164.png
1341840112.445961 rgb/1341840112.445961.png 1341840112.445989 depth/1341840112.445989.png
1341840112.478095 rgb/1341840112.478095.png 1341840112.478125 depth/1341840112.478125.png
1341840112.513947 rgb/1341840112.513947.png 1341840112.513958 depth/1341840112.513958.png
1341840112.545959 rgb/1341840112.545959.png 1341840112.545974 depth/1341840112.545974.png
1341840112.578001 rgb/1341840112.578001.png 1341840112.578013 depth/1341840112.578013.png
1341840112.614023 rgb/1341840112.614023.png 1341840112.614038 depth/1341840112.614038.png
1341840112.646225 rgb/1341840112.646225.png 1341840112.646240 depth/1341840112.646240.png
1341840112.681967 rgb/1341840112.681967.png 1341840112.681983 depth/1341840112.681983.png
1341840112.714010 rgb/1341840112.714010.png 1341840112.714023 depth/1341840112.714023.png
1341840112.746326 rgb/1341840112.746326.png 1341840112.746338 depth/1341840112.746338.png
1341840112.782069 rgb/1341840112.782069.png 1341840112.782089 depth/1341840112.782089.png
1341840112.814160 rgb/1341840112.814160.png 1341840112.814206 depth/1341840112.814206.png
1341840112.846100 rgb/1341840112.846100.png 1341840112.846112 depth/1341840112.846112.png
1341840112.881998 rgb/1341840112.881998.png 1341840112.882008 depth/1341840112.882008.png
1341840112.915647 rgb/1341840112.915647.png 1341840112.917185 depth/1341840112.917185.png
1341840112.950108 rgb/1341840112.950108.png 1341840112.950126 depth/1341840112.950126.png
1341840112.982027 rgb/1341840112.982027.png 1341840112.982051 depth/1341840112.982051.png
1341840113.014038 rgb/1341840113.014038.png 1341840113.014050 depth/1341840113.014050.png
1341840113.050041 rgb/1341840113.050041.png 1341840113.050068 depth/1341840113.050068.png
1341840113.083545 rgb/1341840113.083545.png 1341840113.083560 depth/1341840113.083560.png
1341840113.114465 rgb/1341840113.114465.png 1341840113.114477 depth/1341840113.114477.png
1341840113.149964 rgb/1341840113.149964.png 1341840113.149974 depth/1341840113.149974.png
1341840113.182423 rgb/1341840113.182423.png 1341840113.182446 depth/1341840113.182446.png
1341840113.218045 rgb/1341840113.218045.png 1341840113.218066 depth/1341840113.218066.png
1341840113.250148 rgb/1341840113.250148.png 1341840113.250165 depth/1341840113.250165.png
1341840113.318091 rgb/1341840113.318091.png 1341840113.318111 depth/1341840113.318111.png
1341840113.350264 rgb/1341840113.350264.png 1341840113.350683 depth/1341840113.350683.png
1341840113.382237 rgb/1341840113.382237.png 1341840113.382278 depth/1341840113.382278.png
1341840113.418402 rgb/1341840113.418402.png 1341840113.419275 depth/1341840113.419275.png
1341840113.450286 rgb/1341840113.450286.png 1341840113.450963 depth/1341840113.450963.png
1341840113.486223 rgb/1341840113.486223.png 1341840113.486239 depth/1341840113.486239.png
1341840113.518124 rgb/1341840113.518124.png 1341840113.518650 depth/1341840113.518650.png
1341840113.549959 rgb/1341840113.549959.png 1341840113.550067 depth/1341840113.550067.png
1341840113.586112 rgb/1341840113.586112.png 1341840113.586131 depth/1341840113.586131.png
1341840113.618061 rgb/1341840113.618061.png 1341840113.618088 depth/1341840113.618088.png
1341840113.650118 rgb/1341840113.650118.png 1341840113.650140 depth/1341840113.650140.png
1341840113.686008 rgb/1341840113.686008.png 1341840113.686022 depth/1341840113.686022.png
1341840113.718115 rgb/1341840113.718115.png 1341840113.718800 depth/1341840113.718800.png
1341840113.754016 rgb/1341840113.754016.png 1341840113.754030 depth/1341840113.754030.png
1341840113.786025 rgb/1341840113.786025.png 1341840113.786057 depth/1341840113.786057.png
1341840113.817959 rgb/1341840113.817959.png 1341840113.817982 depth/1341840113.817982.png
1341840113.854018 rgb/1341840113.854018.png 1341840113.854029 depth/1341840113.854029.png
1341840113.886031 rgb/1341840113.886031.png 1341840113.886217 depth/1341840113.886217.png
1341840113.922094 rgb/1341840113.922094.png 1341840113.922108 depth/1341840113.922108.png
1341840113.954013 rgb/1341840113.954013.png 1341840113.954028 depth/1341840113.954028.png
1341840113.986274 rgb/1341840113.986274.png 1341840113.986297 depth/1341840113.986297.png
1341840114.022005 rgb/1341840114.022005.png 1341840114.022449 depth/1341840114.022449.png
1341840114.053984 rgb/1341840114.053984.png 1341840114.054054 depth/1341840114.054054.png
1341840114.086023 rgb/1341840114.086023.png 1341840114.086039 depth/1341840114.086039.png
1341840114.121956 rgb/1341840114.121956.png 1341840114.121978 depth/1341840114.121978.png
1341840114.154055 rgb/1341840114.154055.png 1341840114.154076 depth/1341840114.154076.png
1341840114.190000 rgb/1341840114.190000.png 1341840114.190040 depth/1341840114.190040.png
1341840114.221986 rgb/1341840114.221986.png 1341840114.222013 depth/1341840114.222013.png
1341840114.254034 rgb/1341840114.254034.png 1341840114.254048 depth/1341840114.254048.png
1341840114.290001 rgb/1341840114.290001.png 1341840114.290014 depth/1341840114.290014.png
1341840114.321974 rgb/1341840114.321974.png 1341840114.321983 depth/1341840114.321983.png
1341840114.354115 rgb/1341840114.354115.png 1341840114.354147 depth/1341840114.354147.png
1341840114.390037 rgb/1341840114.390037.png 1341840114.390050 depth/1341840114.390050.png
1341840114.422302 rgb/1341840114.422302.png 1341840114.422416 depth/1341840114.422416.png
1341840114.460071 rgb/1341840114.460071.png 1341840114.460211 depth/1341840114.460211.png
1341840114.490552 rgb/1341840114.490552.png 1341840114.495978 depth/1341840114.495978.png
1341840114.558044 rgb/1341840114.558044.png 1341840114.558075 depth/1341840114.558075.png
1341840114.590103 rgb/1341840114.590103.png 1341840114.590583 depth/1341840114.590583.png
1341840114.622076 rgb/1341840114.622076.png 1341840114.622561 depth/1341840114.622561.png
1341840114.658030 rgb/1341840114.658030.png 1341840114.658054 depth/1341840114.658054.png
1341840114.690158 rgb/1341840114.690158.png 1341840114.690203 depth/1341840114.690203.png
1341840114.726177 rgb/1341840114.726177.png 1341840114.726217 depth/1341840114.726217.png
1341840114.758034 rgb/1341840114.758034.png 1341840114.758058 depth/1341840114.758058.png
1341840114.790483 rgb/1341840114.790483.png 1341840114.790507 depth/1341840114.790507.png
1341840114.826102 rgb/1341840114.826102.png 1341840114.826121 depth/1341840114.826121.png
1341840114.858111 rgb/1341840114.858111.png 1341840114.858135 depth/1341840114.858135.png
1341840114.894167 rgb/1341840114.894167.png 1341840114.894191 depth/1341840114.894191.png
1341840114.926009 rgb/1341840114.926009.png 1341840114.926018 depth/1341840114.926018.png
1341840114.958011 rgb/1341840114.958011.png 1341840114.958019 depth/1341840114.958019.png
1341840114.994015 rgb/1341840114.994015.png 1341840114.994056 depth/1341840114.994056.png
1341840115.026016 rgb/1341840115.026016.png 1341840115.026049 depth/1341840115.026049.png
1341840115.058084 rgb/1341840115.058084.png 1341840115.058112 depth/1341840115.058112.png
1341840115.094064 rgb/1341840115.094064.png 1341840115.094107 depth/1341840115.094107.png
1341840115.126175 rgb/1341840115.126175.png 1341840115.126725 depth/1341840115.126725.png
1341840115.194102 rgb/1341840115.194102.png 1341840115.194156 depth/1341840115.194156.png
1341840115.226005 rgb/1341840115.226005.png 1341840115.226023 depth/1341840115.226023.png
1341840115.262383 rgb/1341840115.262383.png 1341840115.262402 depth/1341840115.262402.png
1341840115.293961 rgb/1341840115.293961.png 1341840115.293975 depth/1341840115.293975.png
1341840115.326039 rgb/1341840115.326039.png 1341840115.326062 depth/1341840115.326062.png
1341840115.362147 rgb/1341840115.362147.png 1341840115.362161 depth/1341840115.362161.png
1341840115.394572 rgb/1341840115.394572.png 1341840115.394598 depth/1341840115.394598.png
1341840115.430115 rgb/1341840115.430115.png 1341840115.430137 depth/1341840115.430137.png
1341840115.462047 rgb/1341840115.462047.png 1341840115.462065 depth/1341840115.462065.png
1341840115.494015 rgb/1341840115.494015.png 1341840115.494032 depth/1341840115.494032.png
1341840115.530138 rgb/1341840115.530138.png 1341840115.530149 depth/1341840115.530149.png
1341840115.562218 rgb/1341840115.562218.png 1341840115.562235 depth/1341840115.562235.png
1341840115.594030 rgb/1341840115.594030.png 1341840115.594042 depth/1341840115.594042.png
1341840115.630134 rgb/1341840115.630134.png 1341840115.630154 depth/1341840115.630154.png
1341840115.662297 rgb/1341840115.662297.png 1341840115.662353 depth/1341840115.662353.png
1341840115.697947 rgb/1341840115.697947.png 1341840115.697958 depth/1341840115.697958.png
1341840115.730048 rgb/1341840115.730048.png 1341840115.730139 depth/1341840115.730139.png
1341840115.762284 rgb/1341840115.762284.png 1341840115.762298 depth/1341840115.762298.png
1341840115.798161 rgb/1341840115.798161.png 1341840115.798198 depth/1341840115.798198.png
1341840115.830276 rgb/1341840115.830276.png 1341840115.830366 depth/1341840115.830366.png
1341840115.862429 rgb/1341840115.862429.png 1341840115.863042 depth/1341840115.863042.png
1341840115.898043 rgb/1341840115.898043.png 1341840115.898066 depth/1341840115.898066.png
1341840115.930014 rgb/1341840115.930014.png 1341840115.930493 depth/1341840115.930493.png
1341840115.966039 rgb/1341840115.966039.png 1341840115.966058 depth/1341840115.966058.png
1341840115.998143 rgb/1341840115.998143.png 1341840115.998912 depth/1341840115.998912.png
1341840116.030797 rgb/1341840116.030797.png 1341840116.030817 depth/1341840116.030817.png
1341840116.066094 rgb/1341840116.066094.png 1341840116.066113 depth/1341840116.066113.png
1341840116.098144 rgb/1341840116.098144.png 1341840116.098169 depth/1341840116.098169.png
1341840116.134127 rgb/1341840116.134127.png 1341840116.134153 depth/1341840116.134153.png
1341840116.166268 rgb/1341840116.166268.png 1341840116.166278 depth/1341840116.166278.png
1341840116.198124 rgb/1341840116.198124.png 1341840116.198152 depth/1341840116.198152.png
1341840116.233931 rgb/1341840116.233931.png 1341840116.233949 depth/1341840116.233949.png
1341840116.266106 rgb/1341840116.266106.png 1341840116.266124 depth/1341840116.266124.png
1341840116.298071 rgb/1341840116.298071.png 1341840116.298105 depth/1341840116.298105.png
1341840116.334029 rgb/1341840116.334029.png 1341840116.334046 depth/1341840116.334046.png
1341840116.366242 rgb/1341840116.366242.png 1341840116.366580 depth/1341840116.366580.png
1341840116.402086 rgb/1341840116.402086.png 1341840116.402630 depth/1341840116.402630.png
1341840116.434026 rgb/1341840116.434026.png 1341840116.434041 depth/1341840116.434041.png
1341840116.466551 rgb/1341840116.466551.png 1341840116.466574 depth/1341840116.466574.png
1341840116.502967 rgb/1341840116.502967.png 1341840116.503008 depth/1341840116.503008.png
1341840116.533901 rgb/1341840116.533901.png 1341840116.533922 depth/1341840116.533922.png
1341840116.566375 rgb/1341840116.566375.png 1341840116.566386 depth/1341840116.566386.png
1341840116.602212 rgb/1341840116.602212.png 1341840116.602848 depth/1341840116.602848.png
1341840116.633966 rgb/1341840116.633966.png 1341840116.633992 depth/1341840116.633992.png
1341840116.670108 rgb/1341840116.670108.png 1341840116.670388 depth/1341840116.670388.png
1341840116.702082 rgb/1341840116.702082.png 1341840116.702097 depth/1341840116.702097.png
1341840116.734125 rgb/1341840116.734125.png 1341840116.734166 depth/1341840116.734166.png
1341840116.770235 rgb/1341840116.770235.png 1341840116.770248 depth/1341840116.770248.png
1341840116.801991 rgb/1341840116.801991.png 1341840116.802014 depth/1341840116.802014.png
1341840116.833908 rgb/1341840116.833908.png 1341840116.833922 depth/1341840116.833922.png
1341840116.870683 rgb/1341840116.870683.png 1341840116.871096 depth/1341840116.871096.png
1341840116.902041 rgb/1341840116.902041.png 1341840116.902061 depth/1341840116.902061.png
1341840116.938059 rgb/1341840116.938059.png 1341840116.938101 depth/1341840116.938101.png
1341840116.970263 rgb/1341840116.970263.png 1341840116.970662 depth/1341840116.970662.png
1341840117.002191 rgb/1341840117.002191.png 1341840117.002207 depth/1341840117.002207.png
1341840117.037960 rgb/1341840117.037960.png 1341840117.037967 depth/1341840117.037967.png
1341840117.070071 rgb/1341840117.070071.png 1341840117.070096 depth/1341840117.070096.png
1341840117.106010 rgb/1341840117.106010.png 1341840117.106024 depth/1341840117.106024.png
1341840117.137909 rgb/1341840117.137909.png 1341840117.137958 depth/1341840117.137958.png
1341840117.170059 rgb/1341840117.170059.png 1341840117.170091 depth/1341840117.170091.png
1341840117.206013 rgb/1341840117.206013.png 1341840117.206026 depth/1341840117.206026.png
1341840117.238051 rgb/1341840117.238051.png 1341840117.238075 depth/1341840117.238075.png
1341840117.270206 rgb/1341840117.270206.png 1341840117.270354 depth/1341840117.270354.png
1341840117.305935 rgb/1341840117.305935.png 1341840117.305972 depth/1341840117.305972.png
1341840117.338033 rgb/1341840117.338033.png 1341840117.338052 depth/1341840117.338052.png
1341840117.374113 rgb/1341840117.374113.png 1341840117.374135 depth/1341840117.374135.png
1341840117.406128 rgb/1341840117.406128.png 1341840117.406387 depth/1341840117.406387.png
1341840117.438051 rgb/1341840117.438051.png 1341840117.438071 depth/1341840117.438071.png
1341840117.474143 rgb/1341840117.474143.png 1341840117.474611 depth/1341840117.474611.png
1341840117.505963 rgb/1341840117.505963.png 1341840117.505989 depth/1341840117.505989.png
1341840117.538068 rgb/1341840117.538068.png 1341840117.538092 depth/1341840117.538092.png
1341840117.574066 rgb/1341840117.574066.png 1341840117.574087 depth/1341840117.574087.png
1341840117.606013 rgb/1341840117.606013.png 1341840117.606029 depth/1341840117.606029.png
1341840117.674073 rgb/1341840117.674073.png 1341840117.674105 depth/1341840117.674105.png
1341840117.706154 rgb/1341840117.706154.png 1341840117.706177 depth/1341840117.706177.png
1341840117.741982 rgb/1341840117.741982.png 1341840117.742013 depth/1341840117.742013.png
1341840117.774097 rgb/1341840117.774097.png 1341840117.774113 depth/1341840117.774113.png
1341840117.806044 rgb/1341840117.806044.png 1341840117.806432 depth/1341840117.806432.png
1341840117.842093 rgb/1341840117.842093.png 1341840117.842112 depth/1341840117.842112.png
1341840117.874196 rgb/1341840117.874196.png 1341840117.874761 depth/1341840117.874761.png
1341840117.910030 rgb/1341840117.910030.png 1341840117.910164 depth/1341840117.910164.png
1341840117.942079 rgb/1341840117.942079.png 1341840117.942099 depth/1341840117.942099.png
1341840117.974032 rgb/1341840117.974032.png 1341840117.974076 depth/1341840117.974076.png
1341840118.010490 rgb/1341840118.010490.png 1341840118.010519 depth/1341840118.010519.png
1341840118.042067 rgb/1341840118.042067.png 1341840118.042081 depth/1341840118.042081.png
1341840118.074033 rgb/1341840118.074033.png 1341840118.074047 depth/1341840118.074047.png
1341840118.110207 rgb/1341840118.110207.png 1341840118.110221 depth/1341840118.110221.png
1341840118.141981 rgb/1341840118.141981.png 1341840118.141994 depth/1341840118.141994.png
1341840118.177996 rgb/1341840118.177996.png 1341840118.178010 depth/1341840118.178010.png
1341840118.210011 rgb/1341840118.210011.png 1341840118.210024 depth/1341840118.210024.png
1341840118.242035 rgb/1341840118.242035.png 1341840118.242049 depth/1341840118.242049.png
1341840118.277926 rgb/1341840118.277926.png 1341840118.277958 depth/1341840118.277958.png
1341840118.310137 rgb/1341840118.310137.png 1341840118.310156 depth/1341840118.310156.png
1341840118.345974 rgb/1341840118.345974.png 1341840118.345988 depth/1341840118.345988.png
1341840118.378027 rgb/1341840118.378027.png 1341840118.378048 depth/1341840118.378048.png
1341840118.410576 rgb/1341840118.410576.png 1341840118.410599 depth/1341840118.410599.png
1341840118.445989 rgb/1341840118.445989.png 1341840118.446042 depth/1341840118.446042.png
1341840118.478134 rgb/1341840118.478134.png 1341840118.478688 depth/1341840118.478688.png
1341840118.509967 rgb/1341840118.509967.png 1341840118.509981 depth/1341840118.509981.png
1341840118.546004 rgb/1341840118.546004.png 1341840118.546016 depth/1341840118.546016.png
1341840118.578056 rgb/1341840118.578056.png 1341840118.578073 depth/1341840118.578073.png
1341840118.614294 rgb/1341840118.614294.png 1341840118.614306 depth/1341840118.614306.png
1341840118.646073 rgb/1341840118.646073.png 1341840118.646095 depth/1341840118.646095.png
1341840118.678010 rgb/1341840118.678010.png 1341840118.678029 depth/1341840118.678029.png
1341840118.714097 rgb/1341840118.714097.png 1341840118.714133 depth/1341840118.714133.png
1341840118.745958 rgb/1341840118.745958.png 1341840118.745980 depth/1341840118.745980.png
1341840118.778020 rgb/1341840118.778020.png 1341840118.778084 depth/1341840118.778084.png
1341840118.814024 rgb/1341840118.814024.png 1341840118.814061 depth/1341840118.814061.png
1341840118.846076 rgb/1341840118.846076.png 1341840118.846088 depth/1341840118.846088.png
1341840118.881984 rgb/1341840118.881984.png 1341840118.881994 depth/1341840118.881994.png
1341840118.914072 rgb/1341840118.914072.png 1341840118.914090 depth/1341840118.914090.png
1341840118.946098 rgb/1341840118.946098.png 1341840118.946110 depth/1341840118.946110.png
1341840118.981987 rgb/1341840118.981987.png 1341840118.982009 depth/1341840118.982009.png
1341840119.014028 rgb/1341840119.014028.png 1341840119.014077 depth/1341840119.014077.png
1341840119.047541 rgb/1341840119.047541.png 1341840119.047554 depth/1341840119.047554.png
1341840119.081995 rgb/1341840119.081995.png 1341840119.082005 depth/1341840119.082005.png
1341840119.114032 rgb/1341840119.114032.png 1341840119.114044 depth/1341840119.114044.png
1341840119.150161 rgb/1341840119.150161.png 1341840119.150181 depth/1341840119.150181.png
1341840119.182054 rgb/1341840119.182054.png 1341840119.182066 depth/1341840119.182066.png
1341840119.214175 rgb/1341840119.214175.png 1341840119.214190 depth/1341840119.214190.png
1341840119.250205 rgb/1341840119.250205.png 1341840119.250217 depth/1341840119.250217.png
1341840119.282047 rgb/1341840119.282047.png 1341840119.282093 depth/1341840119.282093.png
1341840119.318007 rgb/1341840119.318007.png 1341840119.318047 depth/1341840119.318047.png
1341840119.350004 rgb/1341840119.350004.png 1341840119.350146 depth/1341840119.350146.png
1341840119.382084 rgb/1341840119.382084.png 1341840119.382117 depth/1341840119.382117.png
1341840119.418013 rgb/1341840119.418013.png 1341840119.418027 depth/1341840119.418027.png
1341840119.450007 rgb/1341840119.450007.png 1341840119.450087 depth/1341840119.450087.png
1341840119.482124 rgb/1341840119.482124.png 1341840119.482130 depth/1341840119.482130.png
1341840119.517882 rgb/1341840119.517882.png 1341840119.517895 depth/1341840119.517895.png
1341840119.550445 rgb/1341840119.550445.png 1341840119.550679 depth/1341840119.550679.png
1341840119.585989 rgb/1341840119.585989.png 1341840119.586001 depth/1341840119.586001.png
1341840119.618119 rgb/1341840119.618119.png 1341840119.618134 depth/1341840119.618134.png
1341840119.650029 rgb/1341840119.650029.png 1341840119.650052 depth/1341840119.650052.png
1341840119.685955 rgb/1341840119.685955.png 1341840119.685992 depth/1341840119.685992.png
1341840119.717993 rgb/1341840119.717993.png 1341840119.718151 depth/1341840119.718151.png
1341840119.749971 rgb/1341840119.749971.png 1341840119.750486 depth/1341840119.750486.png
1341840119.785854 rgb/1341840119.785854.png 1341840119.785870 depth/1341840119.785870.png
1341840119.818057 rgb/1341840119.818057.png 1341840119.818075 depth/1341840119.818075.png
1341840119.854072 rgb/1341840119.854072.png 1341840119.854090 depth/1341840119.854090.png
1341840119.886031 rgb/1341840119.886031.png 1341840119.886047 depth/1341840119.886047.png
1341840119.918128 rgb/1341840119.918128.png 1341840119.918637 depth/1341840119.918637.png
1341840119.954060 rgb/1341840119.954060.png 1341840119.954093 depth/1341840119.954093.png
1341840119.985974 rgb/1341840119.985974.png 1341840119.986001 depth/1341840119.986001.png
1341840120.018010 rgb/1341840120.018010.png 1341840120.018024 depth/1341840120.018024.png
1341840120.054119 rgb/1341840120.054119.png 1341840120.054132 depth/1341840120.054132.png
1341840120.086075 rgb/1341840120.086075.png 1341840120.086103 depth/1341840120.086103.png
1341840120.122064 rgb/1341840120.122064.png 1341840120.122092 depth/1341840120.122092.png
1341840120.154113 rgb/1341840120.154113.png 1341840120.154169 depth/1341840120.154169.png
1341840120.186050 rgb/1341840120.186050.png 1341840120.186098 depth/1341840120.186098.png
1341840120.221992 rgb/1341840120.221992.png 1341840120.222004 depth/1341840120.222004.png
1341840120.253972 rgb/1341840120.253972.png 1341840120.254426 depth/1341840120.254426.png
1341840120.321993 rgb/1341840120.321993.png 1341840120.322026 depth/1341840120.322026.png
1341840120.354024 rgb/1341840120.354024.png 1341840120.354267 depth/1341840120.354267.png
1341840120.390099 rgb/1341840120.390099.png 1341840120.390141 depth/1341840120.390141.png
1341840120.422028 rgb/1341840120.422028.png 1341840120.422038 depth/1341840120.422038.png
1341840120.454080 rgb/1341840120.454080.png 1341840120.454155 depth/1341840120.454155.png
1341840120.490276 rgb/1341840120.490276.png 1341840120.490299 depth/1341840120.490299.png
1341840120.521961 rgb/1341840120.521961.png 1341840120.521976 depth/1341840120.521976.png
1341840120.558156 rgb/1341840120.558156.png 1341840120.558171 depth/1341840120.558171.png
1341840120.590257 rgb/1341840120.590257.png 1341840120.591136 depth/1341840120.591136.png
1341840120.622049 rgb/1341840120.622049.png 1341840120.622059 depth/1341840120.622059.png
1341840120.658127 rgb/1341840120.658127.png 1341840120.658161 depth/1341840120.658161.png
1341840120.690052 rgb/1341840120.690052.png 1341840120.690072 depth/1341840120.690072.png
1341840120.721967 rgb/1341840120.721967.png 1341840120.721976 depth/1341840120.721976.png
1341840120.758000 rgb/1341840120.758000.png 1341840120.758014 depth/1341840120.758014.png
1341840120.790096 rgb/1341840120.790096.png 1341840120.790119 depth/1341840120.790119.png
1341840120.826121 rgb/1341840120.826121.png 1341840120.826577 depth/1341840120.826577.png
1341840120.858069 rgb/1341840120.858069.png 1341840120.858672 depth/1341840120.858672.png
1341840120.890145 rgb/1341840120.890145.png 1341840120.890395 depth/1341840120.890395.png
1341840120.926172 rgb/1341840120.926172.png 1341840120.926196 depth/1341840120.926196.png
1341840120.958656 rgb/1341840120.958656.png 1341840120.958677 depth/1341840120.958677.png
1341840120.990146 rgb/1341840120.990146.png 1341840120.990247 depth/1341840120.990247.png
1341840121.026124 rgb/1341840121.026124.png 1341840121.026564 depth/1341840121.026564.png
1341840121.058185 rgb/1341840121.058185.png 1341840121.058219 depth/1341840121.058219.png
1341840121.093963 rgb/1341840121.093963.png 1341840121.093980 depth/1341840121.093980.png
1341840121.126130 rgb/1341840121.126130.png 1341840121.126157 depth/1341840121.126157.png
1341840121.158223 rgb/1341840121.158223.png 1341840121.158265 depth/1341840121.158265.png
1341840121.194041 rgb/1341840121.194041.png 1341840121.194533 depth/1341840121.194533.png
1341840121.226164 rgb/1341840121.226164.png 1341840121.226180 depth/1341840121.226180.png
1341840121.258000 rgb/1341840121.258000.png 1341840121.258057 depth/1341840121.258057.png
1341840121.294019 rgb/1341840121.294019.png 1341840121.294402 depth/1341840121.294402.png
1341840121.326012 rgb/1341840121.326012.png 1341840121.326029 depth/1341840121.326029.png
1341840121.362069 rgb/1341840121.362069.png 1341840121.362087 depth/1341840121.362087.png
1341840121.394009 rgb/1341840121.394009.png 1341840121.394022 depth/1341840121.394022.png
1341840121.426047 rgb/1341840121.426047.png 1341840121.426064 depth/1341840121.426064.png
1341840121.461957 rgb/1341840121.461957.png 1341840121.461975 depth/1341840121.461975.png
1341840121.494017 rgb/1341840121.494017.png 1341840121.494027 depth/1341840121.494027.png
1341840121.529928 rgb/1341840121.529928.png 1341840121.529946 depth/1341840121.529946.png
1341840121.562141 rgb/1341840121.562141.png 1341840121.562592 depth/1341840121.562592.png
1341840121.594033 rgb/1341840121.594033.png 1341840121.594046 depth/1341840121.594046.png
1341840121.630041 rgb/1341840121.630041.png 1341840121.630056 depth/1341840121.630056.png
1341840121.661977 rgb/1341840121.661977.png 1341840121.661994 depth/1341840121.661994.png
1341840121.694095 rgb/1341840121.694095.png 1341840121.694120 depth/1341840121.694120.png
1341840121.730237 rgb/1341840121.730237.png 1341840121.730299 depth/1341840121.730299.png
1341840121.761997 rgb/1341840121.761997.png 1341840121.762013 depth/1341840121.762013.png
1341840121.797965 rgb/1341840121.797965.png 1341840121.797981 depth/1341840121.797981.png
1341840121.830074 rgb/1341840121.830074.png 1341840121.830131 depth/1341840121.830131.png
1341840121.862165 rgb/1341840121.862165.png 1341840121.862194 depth/1341840121.862194.png
1341840121.898013 rgb/1341840121.898013.png 1341840121.898031 depth/1341840121.898031.png
1341840121.929981 rgb/1341840121.929981.png 1341840121.929989 depth/1341840121.929989.png
1341840121.962086 rgb/1341840121.962086.png 1341840121.962099 depth/1341840121.962099.png
1341840121.998043 rgb/1341840121.998043.png 1341840121.998062 depth/1341840121.998062.png
1341840122.030127 rgb/1341840122.030127.png 1341840122.030150 depth/1341840122.030150.png
1341840122.066171 rgb/1341840122.066171.png 1341840122.066222 depth/1341840122.066222.png
1341840122.098009 rgb/1341840122.098009.png 1341840122.098035 depth/1341840122.098035.png
1341840122.130073 rgb/1341840122.130073.png 1341840122.130115 depth/1341840122.130115.png
1341840122.166332 rgb/1341840122.166332.png 1341840122.167639 depth/1341840122.167639.png
1341840122.198075 rgb/1341840122.198075.png 1341840122.198694 depth/1341840122.198694.png
1341840122.230015 rgb/1341840122.230015.png 1341840122.230053 depth/1341840122.230053.png
1341840122.266316 rgb/1341840122.266316.png 1341840122.266343 depth/1341840122.266343.png
1341840122.298110 rgb/1341840122.298110.png 1341840122.298128 depth/1341840122.298128.png
1341840122.333997 rgb/1341840122.333997.png 1341840122.334010 depth/1341840122.334010.png
1341840122.366219 rgb/1341840122.366219.png 1341840122.366241 depth/1341840122.366241.png
1341840122.398010 rgb/1341840122.398010.png 1341840122.398019 depth/1341840122.398019.png
1341840122.434144 rgb/1341840122.434144.png 1341840122.434167 depth/1341840122.434167.png
1341840122.466042 rgb/1341840122.466042.png 1341840122.466070 depth/1341840122.466070.png
1341840122.498098 rgb/1341840122.498098.png 1341840122.498115 depth/1341840122.498115.png
1341840122.534119 rgb/1341840122.534119.png 1341840122.534572 depth/1341840122.534572.png
1341840122.565936 rgb/1341840122.565936.png 1341840122.565950 depth/1341840122.565950.png
1341840122.602018 rgb/1341840122.602018.png 1341840122.602035 depth/1341840122.602035.png
1341840122.633950 rgb/1341840122.633950.png 1341840122.633966 depth/1341840122.633966.png
1341840122.665956 rgb/1341840122.665956.png 1341840122.665969 depth/1341840122.665969.png
1341840122.701957 rgb/1341840122.701957.png 1341840122.701967 depth/1341840122.701967.png
1341840122.734093 rgb/1341840122.734093.png 1341840122.734104 depth/1341840122.734104.png
1341840122.770044 rgb/1341840122.770044.png 1341840122.770082 depth/1341840122.770082.png
1341840122.801953 rgb/1341840122.801953.png 1341840122.801979 depth/1341840122.801979.png
1341840122.834016 rgb/1341840122.834016.png 1341840122.834281 depth/1341840122.834281.png
1341840122.870087 rgb/1341840122.870087.png 1341840122.870126 depth/1341840122.870126.png
1341840122.902065 rgb/1341840122.902065.png 1341840122.902090 depth/1341840122.902090.png
1341840122.934003 rgb/1341840122.934003.png 1341840122.934037 depth/1341840122.934037.png
1341840122.970017 rgb/1341840122.970017.png 1341840122.970042 depth/1341840122.970042.png
1341840123.002030 rgb/1341840123.002030.png 1341840123.002045 depth/1341840123.002045.png
1341840123.038065 rgb/1341840123.038065.png 1341840123.038492 depth/1341840123.038492.png
1341840123.070067 rgb/1341840123.070067.png 1341840123.070091 depth/1341840123.070091.png
1341840123.101997 rgb/1341840123.101997.png 1341840123.102017 depth/1341840123.102017.png
1341840123.138121 rgb/1341840123.138121.png 1341840123.138131 depth/1341840123.138131.png
1341840123.169973 rgb/1341840123.169973.png 1341840123.170014 depth/1341840123.170014.png
1341840123.202032 rgb/1341840123.202032.png 1341840123.202068 depth/1341840123.202068.png
1341840123.238122 rgb/1341840123.238122.png 1341840123.238144 depth/1341840123.238144.png
1341840123.269980 rgb/1341840123.269980.png 1341840123.270016 depth/1341840123.270016.png
1341840123.306046 rgb/1341840123.306046.png 1341840123.306136 depth/1341840123.306136.png
1341840123.338004 rgb/1341840123.338004.png 1341840123.338039 depth/1341840123.338039.png
1341840123.371486 rgb/1341840123.371486.png 1341840123.371531 depth/1341840123.371531.png
1341840123.405986 rgb/1341840123.405986.png 1341840123.406012 depth/1341840123.406012.png
1341840123.438009 rgb/1341840123.438009.png 1341840123.438079 depth/1341840123.438079.png
1341840123.470306 rgb/1341840123.470306.png 1341840123.470780 depth/1341840123.470780.png
1341840123.506015 rgb/1341840123.506015.png 1341840123.506039 depth/1341840123.506039.png
1341840123.538113 rgb/1341840123.538113.png 1341840123.538135 depth/1341840123.538135.png
1341840123.574039 rgb/1341840123.574039.png 1341840123.574128 depth/1341840123.574128.png
1341840123.606067 rgb/1341840123.606067.png 1341840123.606087 depth/1341840123.606087.png
1341840123.638023 rgb/1341840123.638023.png 1341840123.638057 depth/1341840123.638057.png
1341840123.673974 rgb/1341840123.673974.png 1341840123.673996 depth/1341840123.673996.png
1341840123.706010 rgb/1341840123.706010.png 1341840123.706032 depth/1341840123.706032.png
1341840123.742381 rgb/1341840123.742381.png 1341840123.742403 depth/1341840123.742403.png
1341840123.774005 rgb/1341840123.774005.png 1341840123.774086 depth/1341840123.774086.png
1341840123.806031 rgb/1341840123.806031.png 1341840123.806045 depth/1341840123.806045.png
1341840123.842043 rgb/1341840123.842043.png 1341840123.842090 depth/1341840123.842090.png
1341840123.874145 rgb/1341840123.874145.png 1341840123.874161 depth/1341840123.874161.png
1341840123.906504 rgb/1341840123.906504.png 1341840123.906514 depth/1341840123.906514.png
1341840123.942274 rgb/1341840123.942274.png 1341840123.942291 depth/1341840123.942291.png
1341840124.010110 rgb/1341840124.010110.png 1341840124.010160 depth/1341840124.010160.png
1341840124.042464 rgb/1341840124.042464.png 1341840124.043010 depth/1341840124.043010.png
1341840124.074278 rgb/1341840124.074278.png 1341840124.074296 depth/1341840124.074296.png
1341840124.109993 rgb/1341840124.109993.png 1341840124.110008 depth/1341840124.110008.png
1341840124.142030 rgb/1341840124.142030.png 1341840124.142044 depth/1341840124.142044.png
1341840124.174717 rgb/1341840124.174717.png 1341840124.174740 depth/1341840124.174740.png
1341840124.210207 rgb/1341840124.210207.png 1341840124.210236 depth/1341840124.210236.png
1341840124.242266 rgb/1341840124.242266.png 1341840124.242301 depth/1341840124.242301.png
1341840124.285051 rgb/1341840124.285051.png 1341840124.278228 depth/1341840124.278228.png
1341840124.342019 rgb/1341840124.342019.png 1341840124.342031 depth/1341840124.342031.png
1341840124.378312 rgb/1341840124.378312.png 1341840124.378334 depth/1341840124.378334.png
1341840124.409939 rgb/1341840124.409939.png 1341840124.409962 depth/1341840124.409962.png
1341840124.442443 rgb/1341840124.442443.png 1341840124.442467 depth/1341840124.442467.png
1341840124.478293 rgb/1341840124.478293.png 1341840124.478323 depth/1341840124.478323.png
1341840124.510263 rgb/1341840124.510263.png 1341840124.510280 depth/1341840124.510280.png
1341840124.546077 rgb/1341840124.546077.png 1341840124.546097 depth/1341840124.546097.png
1341840124.578141 rgb/1341840124.578141.png 1341840124.578153 depth/1341840124.578153.png
1341840124.610089 rgb/1341840124.610089.png 1341840124.610107 depth/1341840124.610107.png
1341840124.646060 rgb/1341840124.646060.png 1341840124.646074 depth/1341840124.646074.png
1341840124.678361 rgb/1341840124.678361.png 1341840124.678376 depth/1341840124.678376.png
1341840124.709971 rgb/1341840124.709971.png 1341840124.709981 depth/1341840124.709981.png
1341840124.745938 rgb/1341840124.745938.png 1341840124.745975 depth/1341840124.745975.png
1341840124.778181 rgb/1341840124.778181.png 1341840124.778194 depth/1341840124.778194.png
1341840124.814087 rgb/1341840124.814087.png 1341840124.814103 depth/1341840124.814103.png
1341840124.846010 rgb/1341840124.846010.png 1341840124.846022 depth/1341840124.846022.png
1341840124.878017 rgb/1341840124.878017.png 1341840124.878573 depth/1341840124.878573.png
1341840124.914181 rgb/1341840124.914181.png 1341840124.914192 depth/1341840124.914192.png
1341840124.946027 rgb/1341840124.946027.png 1341840124.946049 depth/1341840124.946049.png
1341840124.982274 rgb/1341840124.982274.png 1341840124.982298 depth/1341840124.982298.png
1341840125.014063 rgb/1341840125.014063.png 1341840125.014076 depth/1341840125.014076.png
1341840125.046039 rgb/1341840125.046039.png 1341840125.046047 depth/1341840125.046047.png
1341840125.082081 rgb/1341840125.082081.png 1341840125.082097 depth/1341840125.082097.png
1341840125.114038 rgb/1341840125.114038.png 1341840125.114059 depth/1341840125.114059.png
1341840125.146055 rgb/1341840125.146055.png 1341840125.146068 depth/1341840125.146068.png
1341840125.182012 rgb/1341840125.182012.png 1341840125.182027 depth/1341840125.182027.png
1341840125.213996 rgb/1341840125.213996.png 1341840125.214020 depth/1341840125.214020.png
1341840125.250210 rgb/1341840125.250210.png 1341840125.250727 depth/1341840125.250727.png
1341840125.282000 rgb/1341840125.282000.png 1341840125.282014 depth/1341840125.282014.png
1341840125.314051 rgb/1341840125.314051.png 1341840125.314062 depth/1341840125.314062.png
1341840125.349953 rgb/1341840125.349953.png 1341840125.349998 depth/1341840125.349998.png
1341840125.382384 rgb/1341840125.382384.png 1341840125.382396 depth/1341840125.382396.png
1341840125.414021 rgb/1341840125.414021.png 1341840125.414067 depth/1341840125.414067.png
1341840125.450150 rgb/1341840125.450150.png 1341840125.450391 depth/1341840125.450391.png
1341840125.481998 rgb/1341840125.481998.png 1341840125.482040 depth/1341840125.482040.png
1341840125.518104 rgb/1341840125.518104.png 1341840125.518141 depth/1341840125.518141.png
1341840125.549972 rgb/1341840125.549972.png 1341840125.549984 depth/1341840125.549984.png
1341840125.582199 rgb/1341840125.582199.png 1341840125.582983 depth/1341840125.582983.png
1341840125.618068 rgb/1341840125.618068.png 1341840125.618112 depth/1341840125.618112.png
1341840125.650128 rgb/1341840125.650128.png 1341840125.650147 depth/1341840125.650147.png
1341840125.682126 rgb/1341840125.682126.png 1341840125.682134 depth/1341840125.682134.png
1341840125.718114 rgb/1341840125.718114.png 1341840125.718135 depth/1341840125.718135.png
1341840125.750311 rgb/1341840125.750311.png 1341840125.750822 depth/1341840125.750822.png
1341840125.786063 rgb/1341840125.786063.png 1341840125.786077 depth/1341840125.786077.png
1341840125.818005 rgb/1341840125.818005.png 1341840125.818087 depth/1341840125.818087.png
1341840125.849992 rgb/1341840125.849992.png 1341840125.850680 depth/1341840125.850680.png
1341840125.886078 rgb/1341840125.886078.png 1341840125.886652 depth/1341840125.886652.png
1341840125.918028 rgb/1341840125.918028.png 1341840125.918081 depth/1341840125.918081.png
1341840125.954159 rgb/1341840125.954159.png 1341840125.954419 depth/1341840125.954419.png
1341840125.986005 rgb/1341840125.986005.png 1341840125.986014 depth/1341840125.986014.png
1341840126.017980 rgb/1341840126.017980.png 1341840126.017999 depth/1341840126.017999.png
1341840126.054159 rgb/1341840126.054159.png 1341840126.054224 depth/1341840126.054224.png
1341840126.086020 rgb/1341840126.086020.png 1341840126.086035 depth/1341840126.086035.png
1341840126.118088 rgb/1341840126.118088.png 1341840126.118113 depth/1341840126.118113.png
1341840126.154120 rgb/1341840126.154120.png 1341840126.154128 depth/1341840126.154128.png
1341840126.185970 rgb/1341840126.185970.png 1341840126.186028 depth/1341840126.186028.png
1341840126.222058 rgb/1341840126.222058.png 1341840126.222084 depth/1341840126.222084.png
1341840126.254004 rgb/1341840126.254004.png 1341840126.254026 depth/1341840126.254026.png
1341840126.286071 rgb/1341840126.286071.png 1341840126.286083 depth/1341840126.286083.png
1341840126.322149 rgb/1341840126.322149.png 1341840126.322175 depth/1341840126.322175.png
1341840126.386310 rgb/1341840126.386310.png 1341840126.386326 depth/1341840126.386326.png
1341840126.422058 rgb/1341840126.422058.png 1341840126.422081 depth/1341840126.422081.png
1341840126.454093 rgb/1341840126.454093.png 1341840126.454106 depth/1341840126.454106.png
1341840126.490075 rgb/1341840126.490075.png 1341840126.490164 depth/1341840126.490164.png
1341840126.522184 rgb/1341840126.522184.png 1341840126.522642 depth/1341840126.522642.png
1341840126.554439 rgb/1341840126.554439.png 1341840126.555196 depth/1341840126.555196.png
1341840126.590101 rgb/1341840126.590101.png 1341840126.590147 depth/1341840126.590147.png
1341840126.621967 rgb/1341840126.621967.png 1341840126.621994 depth/1341840126.621994.png
1341840126.654071 rgb/1341840126.654071.png 1341840126.654166 depth/1341840126.654166.png
1341840126.690108 rgb/1341840126.690108.png 1341840126.690146 depth/1341840126.690146.png
1341840126.722067 rgb/1341840126.722067.png 1341840126.722077 depth/1341840126.722077.png
1341840126.757975 rgb/1341840126.757975.png 1341840126.758022 depth/1341840126.758022.png
1341840126.789990 rgb/1341840126.789990.png 1341840126.790020 depth/1341840126.790020.png
1341840126.822091 rgb/1341840126.822091.png 1341840126.822110 depth/1341840126.822110.png
1341840126.858075 rgb/1341840126.858075.png 1341840126.858103 depth/1341840126.858103.png
1341840126.890140 rgb/1341840126.890140.png 1341840126.890162 depth/1341840126.890162.png
1341840126.922034 rgb/1341840126.922034.png 1341840126.922068 depth/1341840126.922068.png
1341840126.958061 rgb/1341840126.958061.png 1341840126.958085 depth/1341840126.958085.png
1341840126.990151 rgb/1341840126.990151.png 1341840126.990173 depth/1341840126.990173.png
1341840127.026266 rgb/1341840127.026266.png 1341840127.026290 depth/1341840127.026290.png
1341840127.057963 rgb/1341840127.057963.png 1341840127.058012 depth/1341840127.058012.png
1341840127.089960 rgb/1341840127.089960.png 1341840127.089983 depth/1341840127.089983.png
1341840127.126022 rgb/1341840127.126022.png 1341840127.126130 depth/1341840127.126130.png
1341840127.158030 rgb/1341840127.158030.png 1341840127.158042 depth/1341840127.158042.png
1341840127.194126 rgb/1341840127.194126.png 1341840127.194970 depth/1341840127.194970.png
1341840127.226060 rgb/1341840127.226060.png 1341840127.226089 depth/1341840127.226089.png
1341840127.258260 rgb/1341840127.258260.png 1341840127.258283 depth/1341840127.258283.png
1341840127.293947 rgb/1341840127.293947.png 1341840127.293974 depth/1341840127.293974.png
1341840127.326145 rgb/1341840127.326145.png 1341840127.326164 depth/1341840127.326164.png
1341840127.358234 rgb/1341840127.358234.png 1341840127.358245 depth/1341840127.358245.png
1341840127.394084 rgb/1341840127.394084.png 1341840127.394113 depth/1341840127.394113.png
1341840127.425972 rgb/1341840127.425972.png 1341840127.425999 depth/1341840127.425999.png
1341840127.462026 rgb/1341840127.462026.png 1341840127.462038 depth/1341840127.462038.png
1341840127.494010 rgb/1341840127.494010.png 1341840127.494031 depth/1341840127.494031.png
1341840127.525963 rgb/1341840127.525963.png 1341840127.526030 depth/1341840127.526030.png
1341840127.561982 rgb/1341840127.561982.png 1341840127.561995 depth/1341840127.561995.png
1341840127.594043 rgb/1341840127.594043.png 1341840127.594063 depth/1341840127.594063.png
1341840127.633074 rgb/1341840127.633074.png 1341840127.633089 depth/1341840127.633089.png
1341840127.669383 rgb/1341840127.669383.png 1341840127.670306 depth/1341840127.670306.png
1341840127.730023 rgb/1341840127.730023.png 1341840127.730060 depth/1341840127.730060.png
1341840127.761906 rgb/1341840127.761906.png 1341840127.761919 depth/1341840127.761919.png
1341840127.794112 rgb/1341840127.794112.png 1341840127.794176 depth/1341840127.794176.png
1341840127.830032 rgb/1341840127.830032.png 1341840127.830025 depth/1341840127.830025.png
1341840127.862267 rgb/1341840127.862267.png 1341840127.862782 depth/1341840127.862782.png
1341840127.894060 rgb/1341840127.894060.png 1341840127.894080 depth/1341840127.894080.png
1341840127.930010 rgb/1341840127.930010.png 1341840127.930028 depth/1341840127.930028.png
1341840127.962986 rgb/1341840127.962986.png 1341840127.963035 depth/1341840127.963035.png
1341840127.997999 rgb/1341840127.997999.png 1341840127.998008 depth/1341840127.998008.png
1341840128.030080 rgb/1341840128.030080.png 1341840128.030110 depth/1341840128.030110.png
1341840128.062052 rgb/1341840128.062052.png 1341840128.062062 depth/1341840128.062062.png
1341840128.098032 rgb/1341840128.098032.png 1341840128.098045 depth/1341840128.098045.png
1341840128.130013 rgb/1341840128.130013.png 1341840128.130022 depth/1341840128.130022.png
1341840128.165962 rgb/1341840128.165962.png 1341840128.165992 depth/1341840128.165992.png
1341840128.197950 rgb/1341840128.197950.png 1341840128.197965 depth/1341840128.197965.png
1341840128.230140 rgb/1341840128.230140.png 1341840128.230472 depth/1341840128.230472.png
1341840128.266032 rgb/1341840128.266032.png 1341840128.266045 depth/1341840128.266045.png
1341840128.298015 rgb/1341840128.298015.png 1341840128.298040 depth/1341840128.298040.png
1341840128.330055 rgb/1341840128.330055.png 1341840128.330076 depth/1341840128.330076.png
1341840128.366047 rgb/1341840128.366047.png 1341840128.366061 depth/1341840128.366061.png
1341840128.398051 rgb/1341840128.398051.png 1341840128.398089 depth/1341840128.398089.png
1341840128.434020 rgb/1341840128.434020.png 1341840128.434036 depth/1341840128.434036.png
1341840128.465958 rgb/1341840128.465958.png 1341840128.465974 depth/1341840128.465974.png
1341840128.498139 rgb/1341840128.498139.png 1341840128.498157 depth/1341840128.498157.png
1341840128.534077 rgb/1341840128.534077.png 1341840128.534594 depth/1341840128.534594.png
1341840128.565980 rgb/1341840128.565980.png 1341840128.566009 depth/1341840128.566009.png
1341840128.598334 rgb/1341840128.598334.png 1341840128.598351 depth/1341840128.598351.png
1341840128.634021 rgb/1341840128.634021.png 1341840128.634037 depth/1341840128.634037.png
1341840128.665994 rgb/1341840128.665994.png 1341840128.666029 depth/1341840128.666029.png
1341840128.702088 rgb/1341840128.702088.png 1341840128.702115 depth/1341840128.702115.png
1341840128.734647 rgb/1341840128.734647.png 1341840128.735108 depth/1341840128.735108.png
1341840128.766215 rgb/1341840128.766215.png 1341840128.766958 depth/1341840128.766958.png
1341840128.802328 rgb/1341840128.802328.png 1341840128.802350 depth/1341840128.802350.png
1341840128.834264 rgb/1341840128.834264.png 1341840128.834274 depth/1341840128.834274.png
1341840128.866076 rgb/1341840128.866076.png 1341840128.866101 depth/1341840128.866101.png
1341840128.902014 rgb/1341840128.902014.png 1341840128.902049 depth/1341840128.902049.png
1341840128.934198 rgb/1341840128.934198.png 1341840128.934221 depth/1341840128.934221.png
1341840128.973034 rgb/1341840128.973034.png 1341840128.973048 depth/1341840128.973048.png
1341840129.005075 rgb/1341840129.005075.png 1341840129.005172 depth/1341840129.005172.png
1341840129.041015 rgb/1341840129.041015.png 1341840129.041032 depth/1341840129.041032.png
1341840129.073071 rgb/1341840129.073071.png 1341840129.073096 depth/1341840129.073096.png
1341840129.109000 rgb/1341840129.109000.png 1341840129.109014 depth/1341840129.109014.png
1341840129.141032 rgb/1341840129.141032.png 1341840129.141083 depth/1341840129.141083.png
1341840129.173175 rgb/1341840129.173175.png 1341840129.173202 depth/1341840129.173202.png
1341840129.209154 rgb/1341840129.209154.png 1341840129.209650 depth/1341840129.209650.png
1341840129.240931 rgb/1341840129.240931.png 1341840129.241099 depth/1341840129.241099.png
1341840129.277050 rgb/1341840129.277050.png 1341840129.277063 depth/1341840129.277063.png
1341840129.309035 rgb/1341840129.309035.png 1341840129.309059 depth/1341840129.309059.png
1341840129.340958 rgb/1341840129.340958.png 1341840129.340979 depth/1341840129.340979.png
1341840129.377126 rgb/1341840129.377126.png 1341840129.377929 depth/1341840129.377929.png
1341840129.408991 rgb/1341840129.408991.png 1341840129.409020 depth/1341840129.409020.png
1341840129.445079 rgb/1341840129.445079.png 1341840129.445095 depth/1341840129.445095.png
1341840129.477129 rgb/1341840129.477129.png 1341840129.477146 depth/1341840129.477146.png
1341840129.508931 rgb/1341840129.508931.png 1341840129.508946 depth/1341840129.508946.png
1341840129.545077 rgb/1341840129.545077.png 1341840129.545093 depth/1341840129.545093.png
1341840129.577028 rgb/1341840129.577028.png 1341840129.577466 depth/1341840129.577466.png
1341840129.613105 rgb/1341840129.613105.png 1341840129.613167 depth/1341840129.613167.png
1341840129.645181 rgb/1341840129.645181.png 1341840129.645205 depth/1341840129.645205.png
1341840129.677060 rgb/1341840129.677060.png 1341840129.677076 depth/1341840129.677076.png
1341840129.713150 rgb/1341840129.713150.png 1341840129.713668 depth/1341840129.713668.png
1341840129.781126 rgb/1341840129.781126.png 1341840129.781166 depth/1341840129.781166.png
1341840129.838137 rgb/1341840129.838137.png 1341840129.838163 depth/1341840129.838163.png
1341840129.874190 rgb/1341840129.874190.png 1341840129.874224 depth/1341840129.874224.png
1341840129.905955 rgb/1341840129.905955.png 1341840129.905968 depth/1341840129.905968.png
1341840129.942047 rgb/1341840129.942047.png 1341840129.942070 depth/1341840129.942070.png
1341840129.973973 rgb/1341840129.973973.png 1341840129.973988 depth/1341840129.973988.png
1341840130.042126 rgb/1341840130.042126.png 1341840130.042218 depth/1341840130.042218.png
1341840130.074782 rgb/1341840130.074782.png 1341840130.074828 depth/1341840130.074828.png
1341840130.106036 rgb/1341840130.106036.png 1341840130.106065 depth/1341840130.106065.png
1341840130.142043 rgb/1341840130.142043.png 1341840130.142065 depth/1341840130.142065.png
1341840130.174006 rgb/1341840130.174006.png 1341840130.174019 depth/1341840130.174019.png
1341840130.210173 rgb/1341840130.210173.png 1341840130.210229 depth/1341840130.210229.png
1341840130.241993 rgb/1341840130.241993.png 1341840130.242023 depth/1341840130.242023.png
1341840130.274086 rgb/1341840130.274086.png 1341840130.274120 depth/1341840130.274120.png
1341840130.309975 rgb/1341840130.309975.png 1341840130.310709 depth/1341840130.310709.png
1341840130.349159 rgb/1341840130.349159.png 1341840130.349186 depth/1341840130.349186.png
1341840130.381240 rgb/1341840130.381240.png 1341840130.381851 depth/1341840130.381851.png
1341840130.417035 rgb/1341840130.417035.png 1341840130.417062 depth/1341840130.417062.png
1341840130.449123 rgb/1341840130.449123.png 1341840130.449195 depth/1341840130.449195.png
1341840130.480958 rgb/1341840130.480958.png 1341840130.480976 depth/1341840130.480976.png
1341840130.517090 rgb/1341840130.517090.png 1341840130.517114 depth/1341840130.517114.png
1341840130.549069 rgb/1341840130.549069.png 1341840130.549088 depth/1341840130.549088.png
1341840130.587796 rgb/1341840130.587796.png 1341840130.588274 depth/1341840130.588274.png
1341840130.617146 rgb/1341840130.617146.png 1341840130.617174 depth/1341840130.617174.png
1341840130.649137 rgb/1341840130.649137.png 1341840130.649157 depth/1341840130.649157.png
1341840130.717135 rgb/1341840130.717135.png 1341840130.717190 depth/1341840130.717190.png
1341840130.778114 rgb/1341840130.778114.png 1341840130.778123 depth/1341840130.778123.png
1341840130.810115 rgb/1341840130.810115.png 1341840130.810134 depth/1341840130.810134.png
1341840130.878493 rgb/1341840130.878493.png 1341840130.878509 depth/1341840130.878509.png
1341840130.914115 rgb/1341840130.914115.png 1341840130.914135 depth/1341840130.914135.png
1341840130.946089 rgb/1341840130.946089.png 1341840130.946107 depth/1341840130.946107.png
1341840130.978153 rgb/1341840130.978153.png 1341840130.978179 depth/1341840130.978179.png
1341840131.014063 rgb/1341840131.014063.png 1341840131.014075 depth/1341840131.014075.png
1341840131.046245 rgb/1341840131.046245.png 1341840131.046253 depth/1341840131.046253.png
1341840131.078388 rgb/1341840131.078388.png 1341840131.078422 depth/1341840131.078422.png
1341840131.114122 rgb/1341840131.114122.png 1341840131.114153 depth/1341840131.114153.png
1341840131.146166 rgb/1341840131.146166.png 1341840131.146179 depth/1341840131.146179.png
1341840131.182300 rgb/1341840131.182300.png 1341840131.182321 depth/1341840131.182321.png
1341840131.218982 rgb/1341840131.218982.png 1341840131.219857 depth/1341840131.219857.png
1341840131.282164 rgb/1341840131.282164.png 1341840131.282193 depth/1341840131.282193.png
1341840131.316303 rgb/1341840131.316303.png 1341840131.316324 depth/1341840131.316324.png
1341840131.345970 rgb/1341840131.345970.png 1341840131.346515 depth/1341840131.346515.png
1341840131.382022 rgb/1341840131.382022.png 1341840131.382499 depth/1341840131.382499.png
1341840131.413965 rgb/1341840131.413965.png 1341840131.413983 depth/1341840131.413983.png
1341840131.450200 rgb/1341840131.450200.png 1341840131.450630 depth/1341840131.450630.png
1341840131.482205 rgb/1341840131.482205.png 1341840131.482221 depth/1341840131.482221.png
1341840131.514024 rgb/1341840131.514024.png 1341840131.514122 depth/1341840131.514122.png
1341840131.550027 rgb/1341840131.550027.png 1341840131.550155 depth/1341840131.550155.png
1341840131.582475 rgb/1341840131.582475.png 1341840131.582511 depth/1341840131.582511.png
1341840131.618131 rgb/1341840131.618131.png 1341840131.618150 depth/1341840131.618150.png
1341840131.651356 rgb/1341840131.651356.png 1341840131.651393 depth/1341840131.651393.png
1341840131.682093 rgb/1341840131.682093.png 1341840131.682105 depth/1341840131.682105.png
1341840131.717991 rgb/1341840131.717991.png 1341840131.718033 depth/1341840131.718033.png
1341840131.750781 rgb/1341840131.750781.png 1341840131.751590 depth/1341840131.751590.png
1341840131.781959 rgb/1341840131.781959.png 1341840131.781982 depth/1341840131.781982.png
1341840131.818008 rgb/1341840131.818008.png 1341840131.818034 depth/1341840131.818034.png
1341840131.849988 rgb/1341840131.849988.png 1341840131.850016 depth/1341840131.850016.png
1341840131.886021 rgb/1341840131.886021.png 1341840131.886034 depth/1341840131.886034.png
1341840131.918209 rgb/1341840131.918209.png 1341840131.918254 depth/1341840131.918254.png
1341840131.950157 rgb/1341840131.950157.png 1341840131.950181 depth/1341840131.950181.png
1341840131.986149 rgb/1341840131.986149.png 1341840131.986168 depth/1341840131.986168.png
1341840132.018152 rgb/1341840132.018152.png 1341840132.018168 depth/1341840132.018168.png
1341840132.050105 rgb/1341840132.050105.png 1341840132.050123 depth/1341840132.050123.png
1341840132.086201 rgb/1341840132.086201.png 1341840132.086230 depth/1341840132.086230.png
1341840132.118096 rgb/1341840132.118096.png 1341840132.118108 depth/1341840132.118108.png
1341840132.154105 rgb/1341840132.154105.png 1341840132.154133 depth/1341840132.154133.png
1341840132.186168 rgb/1341840132.186168.png 1341840132.186366 depth/1341840132.186366.png
1341840132.218011 rgb/1341840132.218011.png 1341840132.218021 depth/1341840132.218021.png
1341840132.254237 rgb/1341840132.254237.png 1341840132.254249 depth/1341840132.254249.png
1341840132.285962 rgb/1341840132.285962.png 1341840132.286002 depth/1341840132.286002.png
1341840132.318122 rgb/1341840132.318122.png 1341840132.318135 depth/1341840132.318135.png
1341840132.354146 rgb/1341840132.354146.png 1341840132.354201 depth/1341840132.354201.png
1341840132.386067 rgb/1341840132.386067.png 1341840132.386084 depth/1341840132.386084.png
1341840132.422003 rgb/1341840132.422003.png 1341840132.422433 depth/1341840132.422433.png
1341840132.454101 rgb/1341840132.454101.png 1341840132.454568 depth/1341840132.454568.png
1341840132.486012 rgb/1341840132.486012.png 1341840132.486032 depth/1341840132.486032.png
1341840132.522171 rgb/1341840132.522171.png 1341840132.522201 depth/1341840132.522201.png
1341840132.554000 rgb/1341840132.554000.png 1341840132.554033 depth/1341840132.554033.png
1341840132.590191 rgb/1341840132.590191.png 1341840132.590210 depth/1341840132.590210.png
1341840132.621972 rgb/1341840132.621972.png 1341840132.621987 depth/1341840132.621987.png
1341840132.654055 rgb/1341840132.654055.png 1341840132.654074 depth/1341840132.654074.png
1341840132.690063 rgb/1341840132.690063.png 1341840132.690077 depth/1341840132.690077.png
1341840132.722060 rgb/1341840132.722060.png 1341840132.722148 depth/1341840132.722148.png
1341840132.754009 rgb/1341840132.754009.png 1341840132.754032 depth/1341840132.754032.png
1341840132.790126 rgb/1341840132.790126.png 1341840132.790141 depth/1341840132.790141.png
1341840132.822165 rgb/1341840132.822165.png 1341840132.822179 depth/1341840132.822179.png
1341840132.858128 rgb/1341840132.858128.png 1341840132.858135 depth/1341840132.858135.png
1341840132.890074 rgb/1341840132.890074.png 1341840132.890103 depth/1341840132.890103.png
1341840132.922331 rgb/1341840132.922331.png 1341840132.922355 depth/1341840132.922355.png
1341840132.958143 rgb/1341840132.958143.png 1341840132.958161 depth/1341840132.958161.png
1341840132.990011 rgb/1341840132.990011.png 1341840132.990591 depth/1341840132.990591.png
1341840133.022123 rgb/1341840133.022123.png 1341840133.022177 depth/1341840133.022177.png
1341840133.058116 rgb/1341840133.058116.png 1341840133.058125 depth/1341840133.058125.png
1341840133.089991 rgb/1341840133.089991.png 1341840133.090022 depth/1341840133.090022.png
1341840133.126100 rgb/1341840133.126100.png 1341840133.126162 depth/1341840133.126162.png
1341840133.158041 rgb/1341840133.158041.png 1341840133.158072 depth/1341840133.158072.png
1341840133.190165 rgb/1341840133.190165.png 1341840133.190179 depth/1341840133.190179.png
1341840133.226039 rgb/1341840133.226039.png 1341840133.226058 depth/1341840133.226058.png
1341840133.258020 rgb/1341840133.258020.png 1341840133.258090 depth/1341840133.258090.png
1341840133.290010 rgb/1341840133.290010.png 1341840133.290036 depth/1341840133.290036.png
1341840133.326121 rgb/1341840133.326121.png 1341840133.326132 depth/1341840133.326132.png
1341840133.357973 rgb/1341840133.357973.png 1341840133.357984 depth/1341840133.357984.png
1341840133.394143 rgb/1341840133.394143.png 1341840133.394710 depth/1341840133.394710.png
1341840133.426653 rgb/1341840133.426653.png 1341840133.426668 depth/1341840133.426668.png
1341840133.458017 rgb/1341840133.458017.png 1341840133.458039 depth/1341840133.458039.png
1341840133.494056 rgb/1341840133.494056.png 1341840133.494150 depth/1341840133.494150.png
1341840133.526138 rgb/1341840133.526138.png 1341840133.526146 depth/1341840133.526146.png
1341840133.558093 rgb/1341840133.558093.png 1341840133.558130 depth/1341840133.558130.png
1341840133.596989 rgb/1341840133.596989.png 1341840133.594145 depth/1341840133.594145.png
1341840133.662163 rgb/1341840133.662163.png 1341840133.662190 depth/1341840133.662190.png
1341840133.694287 rgb/1341840133.694287.png 1341840133.694320 depth/1341840133.694320.png
1341840133.725972 rgb/1341840133.725972.png 1341840133.726028 depth/1341840133.726028.png
1341840133.762031 rgb/1341840133.762031.png 1341840133.762039 depth/1341840133.762039.png
1341840133.794303 rgb/1341840133.794303.png 1341840133.794324 depth/1341840133.794324.png
1341840133.830078 rgb/1341840133.830078.png 1341840133.830093 depth/1341840133.830093.png
1341840133.862082 rgb/1341840133.862082.png 1341840133.862122 depth/1341840133.862122.png
1341840133.895671 rgb/1341840133.895671.png 1341840133.896407 depth/1341840133.896407.png
1341840133.962170 rgb/1341840133.962170.png 1341840133.962189 depth/1341840133.962189.png
1341840133.994096 rgb/1341840133.994096.png 1341840133.994150 depth/1341840133.994150.png
1341840134.030081 rgb/1341840134.030081.png 1341840134.030176 depth/1341840134.030176.png
1341840134.062064 rgb/1341840134.062064.png 1341840134.062089 depth/1341840134.062089.png
1341840134.098505 rgb/1341840134.098505.png 1341840134.098539 depth/1341840134.098539.png
1341840134.130096 rgb/1341840134.130096.png 1341840134.130230 depth/1341840134.130230.png
1341840134.162042 rgb/1341840134.162042.png 1341840134.162111 depth/1341840134.162111.png
1341840134.198214 rgb/1341840134.198214.png 1341840134.198229 depth/1341840134.198229.png
1341840134.230132 rgb/1341840134.230132.png 1341840134.230987 depth/1341840134.230987.png
1341840134.262049 rgb/1341840134.262049.png 1341840134.262088 depth/1341840134.262088.png
1341840134.297987 rgb/1341840134.297987.png 1341840134.298003 depth/1341840134.298003.png
1341840134.330137 rgb/1341840134.330137.png 1341840134.331272 depth/1341840134.331272.png
1341840134.366116 rgb/1341840134.366116.png 1341840134.366131 depth/1341840134.366131.png
1341840134.430407 rgb/1341840134.430407.png 1341840134.430483 depth/1341840134.430483.png
1341840134.466088 rgb/1341840134.466088.png 1341840134.466829 depth/1341840134.466829.png
1341840134.498028 rgb/1341840134.498028.png 1341840134.498043 depth/1341840134.498043.png
1341840134.530063 rgb/1341840134.530063.png 1341840134.530084 depth/1341840134.530084.png
1341840134.565976 rgb/1341840134.565976.png 1341840134.566006 depth/1341840134.566006.png
1341840134.598132 rgb/1341840134.598132.png 1341840134.598150 depth/1341840134.598150.png
1341840134.634118 rgb/1341840134.634118.png 1341840134.634125 depth/1341840134.634125.png
1341840134.666094 rgb/1341840134.666094.png 1341840134.666601 depth/1341840134.666601.png
1341840134.698325 rgb/1341840134.698325.png 1341840134.698366 depth/1341840134.698366.png
1341840134.733994 rgb/1341840134.733994.png 1341840134.734009 depth/1341840134.734009.png
1341840134.766613 rgb/1341840134.766613.png 1341840134.766622 depth/1341840134.766622.png
1341840134.802097 rgb/1341840134.802097.png 1341840134.802131 depth/1341840134.802131.png
1341840134.833989 rgb/1341840134.833989.png 1341840134.834005 depth/1341840134.834005.png
1341840134.866184 rgb/1341840134.866184.png 1341840134.866193 depth/1341840134.866193.png
1341840134.902070 rgb/1341840134.902070.png 1341840134.902084 depth/1341840134.902084.png
1341840134.933969 rgb/1341840134.933969.png 1341840134.933980 depth/1341840134.933980.png
1341840134.966029 rgb/1341840134.966029.png 1341840134.966063 depth/1341840134.966063.png
1341840135.001944 rgb/1341840135.001944.png 1341840135.001953 depth/1341840135.001953.png
1341840135.034464 rgb/1341840135.034464.png 1341840135.034490 depth/1341840135.034490.png
1341840135.069989 rgb/1341840135.069989.png 1341840135.070007 depth/1341840135.070007.png
1341840135.102037 rgb/1341840135.102037.png 1341840135.102085 depth/1341840135.102085.png
1341840135.133985 rgb/1341840135.133985.png 1341840135.134008 depth/1341840135.134008.png
1341840135.170148 rgb/1341840135.170148.png 1341840135.170187 depth/1341840135.170187.png
1341840135.202073 rgb/1341840135.202073.png 1341840135.202155 depth/1341840135.202155.png
1341840135.234309 rgb/1341840135.234309.png 1341840135.234351 depth/1341840135.234351.png
1341840135.270093 rgb/1341840135.270093.png 1341840135.270108 depth/1341840135.270108.png
1341840135.302100 rgb/1341840135.302100.png 1341840135.302118 depth/1341840135.302118.png
1341840135.338325 rgb/1341840135.338325.png 1341840135.338355 depth/1341840135.338355.png
1341840135.370144 rgb/1341840135.370144.png 1341840135.370170 depth/1341840135.370170.png
1341840135.402042 rgb/1341840135.402042.png 1341840135.402659 depth/1341840135.402659.png
1341840135.437978 rgb/1341840135.437978.png 1341840135.437993 depth/1341840135.437993.png
1341840135.470019 rgb/1341840135.470019.png 1341840135.470040 depth/1341840135.470040.png
1341840135.502169 rgb/1341840135.502169.png 1341840135.502734 depth/1341840135.502734.png
1341840135.538089 rgb/1341840135.538089.png 1341840135.538102 depth/1341840135.538102.png
1341840135.570157 rgb/1341840135.570157.png 1341840135.570173 depth/1341840135.570173.png
1341840135.606052 rgb/1341840135.606052.png 1341840135.606062 depth/1341840135.606062.png
1341840135.638227 rgb/1341840135.638227.png 1341840135.638241 depth/1341840135.638241.png
1341840135.670239 rgb/1341840135.670239.png 1341840135.670311 depth/1341840135.670311.png
1341840135.706052 rgb/1341840135.706052.png 1341840135.706516 depth/1341840135.706516.png
1341840135.738137 rgb/1341840135.738137.png 1341840135.738161 depth/1341840135.738161.png
1341840135.774040 rgb/1341840135.774040.png 1341840135.774050 depth/1341840135.774050.png
1341840135.806028 rgb/1341840135.806028.png 1341840135.806051 depth/1341840135.806051.png
1341840135.838206 rgb/1341840135.838206.png 1341840135.838217 depth/1341840135.838217.png
1341840135.874119 rgb/1341840135.874119.png 1341840135.874132 depth/1341840135.874132.png
1341840135.906010 rgb/1341840135.906010.png 1341840135.906030 depth/1341840135.906030.png
1341840135.938279 rgb/1341840135.938279.png 1341840135.938292 depth/1341840135.938292.png
1341840135.974129 rgb/1341840135.974129.png 1341840135.974151 depth/1341840135.974151.png
1341840136.006161 rgb/1341840136.006161.png 1341840136.006195 depth/1341840136.006195.png
1341840136.042013 rgb/1341840136.042013.png 1341840136.042143 depth/1341840136.042143.png
1341840136.074071 rgb/1341840136.074071.png 1341840136.074085 depth/1341840136.074085.png
1341840136.106147 rgb/1341840136.106147.png 1341840136.106212 depth/1341840136.106212.png
1341840136.142085 rgb/1341840136.142085.png 1341840136.142129 depth/1341840136.142129.png
1341840136.174142 rgb/1341840136.174142.png 1341840136.174163 depth/1341840136.174163.png
1341840136.206178 rgb/1341840136.206178.png 1341840136.206233 depth/1341840136.206233.png
1341840136.242129 rgb/1341840136.242129.png 1341840136.242172 depth/1341840136.242172.png
1341840136.274146 rgb/1341840136.274146.png 1341840136.274191 depth/1341840136.274191.png
1341840136.310044 rgb/1341840136.310044.png 1341840136.310234 depth/1341840136.310234.png
1341840136.342103 rgb/1341840136.342103.png 1341840136.342117 depth/1341840136.342117.png
1341840136.374144 rgb/1341840136.374144.png 1341840136.374202 depth/1341840136.374202.png
1341840136.410181 rgb/1341840136.410181.png 1341840136.410200 depth/1341840136.410200.png
1341840136.442000 rgb/1341840136.442000.png 1341840136.442059 depth/1341840136.442059.png
1341840136.474110 rgb/1341840136.474110.png 1341840136.474124 depth/1341840136.474124.png
1341840136.510086 rgb/1341840136.510086.png 1341840136.510106 depth/1341840136.510106.png
1341840136.542096 rgb/1341840136.542096.png 1341840136.542112 depth/1341840136.542112.png
1341840136.578053 rgb/1341840136.578053.png 1341840136.578068 depth/1341840136.578068.png
1341840136.609971 rgb/1341840136.609971.png 1341840136.609979 depth/1341840136.609979.png
1341840136.642106 rgb/1341840136.642106.png 1341840136.642125 depth/1341840136.642125.png
1341840136.678116 rgb/1341840136.678116.png 1341840136.678127 depth/1341840136.678127.png
1341840136.709984 rgb/1341840136.709984.png 1341840136.709994 depth/1341840136.709994.png
1341840136.742055 rgb/1341840136.742055.png 1341840136.742064 depth/1341840136.742064.png
1341840136.778016 rgb/1341840136.778016.png 1341840136.778035 depth/1341840136.778035.png
1341840136.810073 rgb/1341840136.810073.png 1341840136.810965 depth/1341840136.810965.png
1341840136.846014 rgb/1341840136.846014.png 1341840136.846034 depth/1341840136.846034.png
1341840136.878703 rgb/1341840136.878703.png 1341840136.878714 depth/1341840136.878714.png
1341840136.910068 rgb/1341840136.910068.png 1341840136.910089 depth/1341840136.910089.png
1341840136.946101 rgb/1341840136.946101.png 1341840136.946121 depth/1341840136.946121.png
1341840136.978140 rgb/1341840136.978140.png 1341840136.978157 depth/1341840136.978157.png
1341840137.013946 rgb/1341840137.013946.png 1341840137.013963 depth/1341840137.013963.png
1341840137.046197 rgb/1341840137.046197.png 1341840137.046216 depth/1341840137.046216.png
1341840137.078105 rgb/1341840137.078105.png 1341840137.078117 depth/1341840137.078117.png
1341840137.114118 rgb/1341840137.114118.png 1341840137.114202 depth/1341840137.114202.png
1341840137.146012 rgb/1341840137.146012.png 1341840137.146037 depth/1341840137.146037.png
1341840137.178130 rgb/1341840137.178130.png 1341840137.178154 depth/1341840137.178154.png
1341840137.213973 rgb/1341840137.213973.png 1341840137.213980 depth/1341840137.213980.png
1341840137.246123 rgb/1341840137.246123.png 1341840137.246146 depth/1341840137.246146.png
1341840137.282211 rgb/1341840137.282211.png 1341840137.282226 depth/1341840137.282226.png
1341840137.350557 rgb/1341840137.350557.png 1341840137.350605 depth/1341840137.350605.png
1341840137.389297 rgb/1341840137.389297.png 1341840137.389313 depth/1341840137.389313.png
1341840137.421483 rgb/1341840137.421483.png 1341840137.423346 depth/1341840137.423346.png
1341840137.453379 rgb/1341840137.453379.png 1341840137.453391 depth/1341840137.453391.png
1341840137.489294 rgb/1341840137.489294.png 1341840137.490706 depth/1341840137.490706.png
1341840137.523409 rgb/1341840137.523409.png 1341840137.524388 depth/1341840137.524388.png
1341840137.553325 rgb/1341840137.553325.png 1341840137.554086 depth/1341840137.554086.png
1341840137.589470 rgb/1341840137.589470.png 1341840137.590698 depth/1341840137.590698.png
1341840137.624008 rgb/1341840137.624008.png 1341840137.627245 depth/1341840137.627245.png
1341840137.657522 rgb/1341840137.657522.png 1341840137.658733 depth/1341840137.658733.png
1341840137.689342 rgb/1341840137.689342.png 1341840137.694598 depth/1341840137.694598.png
1341840137.721926 rgb/1341840137.721926.png 1341840137.722404 depth/1341840137.722404.png
1341840137.759587 rgb/1341840137.759587.png 1341840137.761018 depth/1341840137.761018.png
1341840137.790775 rgb/1341840137.790775.png 1341840137.791879 depth/1341840137.791879.png
1341840137.821916 rgb/1341840137.821916.png 1341840137.823316 depth/1341840137.823316.png
1341840137.861516 rgb/1341840137.861516.png 1341840137.862810 depth/1341840137.862810.png
1341840137.893812 rgb/1341840137.893812.png 1341840137.893950 depth/1341840137.893950.png
1341840137.925612 rgb/1341840137.925612.png 1341840137.926839 depth/1341840137.926839.png
1341840137.956989 rgb/1341840137.956989.png 1341840137.957020 depth/1341840137.957020.png
1341840137.989242 rgb/1341840137.989242.png 1341840137.989251 depth/1341840137.989251.png
1341840138.025120 rgb/1341840138.025120.png 1341840138.025135 depth/1341840138.025135.png
1341840138.058067 rgb/1341840138.058067.png 1341840138.058115 depth/1341840138.058115.png
1341840138.089228 rgb/1341840138.089228.png 1341840138.090752 depth/1341840138.090752.png
1341840138.125193 rgb/1341840138.125193.png 1341840138.125208 depth/1341840138.125208.png
1341840138.157187 rgb/1341840138.157187.png 1341840138.157207 depth/1341840138.157207.png
1341840138.189146 rgb/1341840138.189146.png 1341840138.189169 depth/1341840138.189169.png
1341840138.224979 rgb/1341840138.224979.png 1341840138.224998 depth/1341840138.224998.png
1341840138.257038 rgb/1341840138.257038.png 1341840138.257049 depth/1341840138.257049.png
1341840138.293190 rgb/1341840138.293190.png 1341840138.293207 depth/1341840138.293207.png
1341840138.325109 rgb/1341840138.325109.png 1341840138.325141 depth/1341840138.325141.png
1341840138.356973 rgb/1341840138.356973.png 1341840138.356994 depth/1341840138.356994.png
1341840138.392961 rgb/1341840138.392961.png 1341840138.392974 depth/1341840138.392974.png
1341840138.425035 rgb/1341840138.425035.png 1341840138.425650 depth/1341840138.425650.png
1341840138.457058 rgb/1341840138.457058.png 1341840138.457077 depth/1341840138.457077.png
1341840138.493018 rgb/1341840138.493018.png 1341840138.493028 depth/1341840138.493028.png
1341840138.524956 rgb/1341840138.524956.png 1341840138.524964 depth/1341840138.524964.png
1341840138.557167 rgb/1341840138.557167.png 1341840138.557180 depth/1341840138.557180.png
1341840138.593089 rgb/1341840138.593089.png 1341840138.593102 depth/1341840138.593102.png
1341840138.624938 rgb/1341840138.624938.png 1341840138.624972 depth/1341840138.624972.png
1341840138.661032 rgb/1341840138.661032.png 1341840138.661046 depth/1341840138.661046.png
1341840138.693089 rgb/1341840138.693089.png 1341840138.693109 depth/1341840138.693109.png
1341840138.725002 rgb/1341840138.725002.png 1341840138.725059 depth/1341840138.725059.png
1341840138.761074 rgb/1341840138.761074.png 1341840138.761086 depth/1341840138.761086.png
1341840138.793033 rgb/1341840138.793033.png 1341840138.793053 depth/1341840138.793053.png
1341840138.825178 rgb/1341840138.825178.png 1341840138.825198 depth/1341840138.825198.png
1341840138.861281 rgb/1341840138.861281.png 1341840138.861291 depth/1341840138.861291.png
1341840138.893162 rgb/1341840138.893162.png 1341840138.893821 depth/1341840138.893821.png
1341840138.929074 rgb/1341840138.929074.png 1341840138.929087 depth/1341840138.929087.png
1341840138.961069 rgb/1341840138.961069.png 1341840138.961079 depth/1341840138.961079.png
1341840138.993385 rgb/1341840138.993385.png 1341840138.993418 depth/1341840138.993418.png
1341840139.028984 rgb/1341840139.028984.png 1341840139.028993 depth/1341840139.028993.png
1341840139.061014 rgb/1341840139.061014.png 1341840139.061027 depth/1341840139.061027.png
1341840139.097254 rgb/1341840139.097254.png 1341840139.097274 depth/1341840139.097274.png
1341840139.129091 rgb/1341840139.129091.png 1341840139.129099 depth/1341840139.129099.png
1341840139.160945 rgb/1341840139.160945.png 1341840139.160955 depth/1341840139.160955.png
1341840139.196990 rgb/1341840139.196990.png 1341840139.196998 depth/1341840139.196998.png
1341840139.228998 rgb/1341840139.228998.png 1341840139.229010 depth/1341840139.229010.png
1341840139.265069 rgb/1341840139.265069.png 1341840139.265081 depth/1341840139.265081.png
1341840139.297244 rgb/1341840139.297244.png 1341840139.297259 depth/1341840139.297259.png
1341840139.334563 rgb/1341840139.334563.png 1341840139.335398 depth/1341840139.335398.png
1341840139.365300 rgb/1341840139.365300.png 1341840139.365330 depth/1341840139.365330.png
1341840139.433146 rgb/1341840139.433146.png 1341840139.433184 depth/1341840139.433184.png
1341840139.494120 rgb/1341840139.494120.png 1341840139.494169 depth/1341840139.494169.png
1341840139.525955 rgb/1341840139.525955.png 1341840139.526012 depth/1341840139.526012.png
1341840139.557968 rgb/1341840139.557968.png 1341840139.557982 depth/1341840139.557982.png
1341840139.594119 rgb/1341840139.594119.png 1341840139.594130 depth/1341840139.594130.png
1341840139.626042 rgb/1341840139.626042.png 1341840139.626059 depth/1341840139.626059.png
1341840139.726297 rgb/1341840139.726297.png 1341840139.726312 depth/1341840139.726312.png
1341840139.762004 rgb/1341840139.762004.png 1341840139.762018 depth/1341840139.762018.png
1341840139.794398 rgb/1341840139.794398.png 1341840139.794410 depth/1341840139.794410.png
1341840139.826732 rgb/1341840139.826732.png 1341840139.826743 depth/1341840139.826743.png
1341840139.862007 rgb/1341840139.862007.png 1341840139.862019 depth/1341840139.862019.png
1341840139.894244 rgb/1341840139.894244.png 1341840139.894300 depth/1341840139.894300.png
1341840139.926058 rgb/1341840139.926058.png 1341840139.926081 depth/1341840139.926081.png
1341840139.961989 rgb/1341840139.961989.png 1341840139.962034 depth/1341840139.962034.png
1341840139.994508 rgb/1341840139.994508.png 1341840139.994517 depth/1341840139.994517.png
1341840140.030374 rgb/1341840140.030374.png 1341840140.030433 depth/1341840140.030433.png
1341840140.062130 rgb/1341840140.062130.png 1341840140.062143 depth/1341840140.062143.png
1341840140.094164 rgb/1341840140.094164.png 1341840140.094177 depth/1341840140.094177.png
1341840140.130166 rgb/1341840140.130166.png 1341840140.130176 depth/1341840140.130176.png
1341840140.162059 rgb/1341840140.162059.png 1341840140.162074 depth/1341840140.162074.png
1341840140.197991 rgb/1341840140.197991.png 1341840140.198001 depth/1341840140.198001.png
1341840140.230198 rgb/1341840140.230198.png 1341840140.230212 depth/1341840140.230212.png
1341840140.262494 rgb/1341840140.262494.png 1341840140.262580 depth/1341840140.262580.png
1341840140.298172 rgb/1341840140.298172.png 1341840140.298211 depth/1341840140.298211.png
1341840140.330071 rgb/1341840140.330071.png 1341840140.330091 depth/1341840140.330091.png
1341840140.362068 rgb/1341840140.362068.png 1341840140.362081 depth/1341840140.362081.png
================================================
FILE: Examples/RGB-D/associations/fr3_office.txt
================================================
1341847980.722988 rgb/1341847980.722988.png 1341847980.723020 depth/1341847980.723020.png
1341847980.754743 rgb/1341847980.754743.png 1341847980.754755 depth/1341847980.754755.png
1341847980.786856 rgb/1341847980.786856.png 1341847980.786879 depth/1341847980.786879.png
1341847980.822978 rgb/1341847980.822978.png 1341847980.822989 depth/1341847980.822989.png
1341847980.854676 rgb/1341847980.854676.png 1341847980.854690 depth/1341847980.854690.png
1341847980.890728 rgb/1341847980.890728.png 1341847980.890737 depth/1341847980.890737.png
1341847980.922978 rgb/1341847980.922978.png 1341847980.922989 depth/1341847980.922989.png
1341847980.954645 rgb/1341847980.954645.png 1341847980.954676 depth/1341847980.954676.png
1341847980.990699 rgb/1341847980.990699.png 1341847980.990724 depth/1341847980.990724.png
1341847981.022715 rgb/1341847981.022715.png 1341847981.022728 depth/1341847981.022728.png
1341847981.054711 rgb/1341847981.054711.png 1341847981.054773 depth/1341847981.054773.png
1341847981.090715 rgb/1341847981.090715.png 1341847981.090786 depth/1341847981.090786.png
1341847981.122985 rgb/1341847981.122985.png 1341847981.123049 depth/1341847981.123049.png
1341847981.158632 rgb/1341847981.158632.png 1341847981.158648 depth/1341847981.158648.png
1341847981.190636 rgb/1341847981.190636.png 1341847981.190650 depth/1341847981.190650.png
1341847981.222978 rgb/1341847981.222978.png 1341847981.222989 depth/1341847981.222989.png
1341847981.258722 rgb/1341847981.258722.png 1341847981.258781 depth/1341847981.258781.png
1341847981.290787 rgb/1341847981.290787.png 1341847981.290854 depth/1341847981.290854.png
1341847981.322892 rgb/1341847981.322892.png 1341847981.322934 depth/1341847981.322934.png
1341847981.358690 rgb/1341847981.358690.png 1341847981.358724 depth/1341847981.358724.png
1341847981.390810 rgb/1341847981.390810.png 1341847981.390852 depth/1341847981.390852.png
1341847981.426707 rgb/1341847981.426707.png 1341847981.426732 depth/1341847981.426732.png
1341847981.458797 rgb/1341847981.458797.png 1341847981.459399 depth/1341847981.459399.png
1341847981.490701 rgb/1341847981.490701.png 1341847981.493435 depth/1341847981.493435.png
1341847981.527039 rgb/1341847981.527039.png 1341847981.527062 depth/1341847981.527062.png
1341847981.558722 rgb/1341847981.558722.png 1341847981.558770 depth/1341847981.558770.png
1341847981.594855 rgb/1341847981.594855.png 1341847981.594880 depth/1341847981.594880.png
1341847981.626675 rgb/1341847981.626675.png 1341847981.626685 depth/1341847981.626685.png
1341847981.658738 rgb/1341847981.658738.png 1341847981.658793 depth/1341847981.658793.png
1341847981.694720 rgb/1341847981.694720.png 1341847981.694765 depth/1341847981.694765.png
1341847981.726650 rgb/1341847981.726650.png 1341847981.726727 depth/1341847981.726727.png
1341847981.758846 rgb/1341847981.758846.png 1341847981.758922 depth/1341847981.758922.png
1341847981.794659 rgb/1341847981.794659.png 1341847981.794679 depth/1341847981.794679.png
1341847981.826678 rgb/1341847981.826678.png 1341847981.826688 depth/1341847981.826688.png
1341847981.862719 rgb/1341847981.862719.png 1341847981.862742 depth/1341847981.862742.png
1341847981.894631 rgb/1341847981.894631.png 1341847981.894645 depth/1341847981.894645.png
1341847981.926602 rgb/1341847981.926602.png 1341847981.927087 depth/1341847981.927087.png
1341847981.994808 rgb/1341847981.994808.png 1341847981.994858 depth/1341847981.994858.png
1341847982.062739 rgb/1341847982.062739.png 1341847982.062794 depth/1341847982.062794.png
1341847982.094786 rgb/1341847982.094786.png 1341847982.095304 depth/1341847982.095304.png
1341847982.130710 rgb/1341847982.130710.png 1341847982.130739 depth/1341847982.130739.png
1341847982.162730 rgb/1341847982.162730.png 1341847982.162746 depth/1341847982.162746.png
1341847982.194674 rgb/1341847982.194674.png 1341847982.194690 depth/1341847982.194690.png
1341847982.230594 rgb/1341847982.230594.png 1341847982.230626 depth/1341847982.230626.png
1341847982.262666 rgb/1341847982.262666.png 1341847982.262694 depth/1341847982.262694.png
1341847982.294994 rgb/1341847982.294994.png 1341847982.295020 depth/1341847982.295020.png
1341847982.330655 rgb/1341847982.330655.png 1341847982.330680 depth/1341847982.330680.png
1341847982.398909 rgb/1341847982.398909.png 1341847982.398929 depth/1341847982.398929.png
1341847982.430770 rgb/1341847982.430770.png 1341847982.430799 depth/1341847982.430799.png
1341847982.462624 rgb/1341847982.462624.png 1341847982.462632 depth/1341847982.462632.png
1341847982.498616 rgb/1341847982.498616.png 1341847982.498627 depth/1341847982.498627.png
1341847982.530757 rgb/1341847982.530757.png 1341847982.530781 depth/1341847982.530781.png
1341847982.566660 rgb/1341847982.566660.png 1341847982.566676 depth/1341847982.566676.png
1341847982.598726 rgb/1341847982.598726.png 1341847982.598757 depth/1341847982.598757.png
1341847982.630723 rgb/1341847982.630723.png 1341847982.630827 depth/1341847982.630827.png
1341847982.666620 rgb/1341847982.666620.png 1341847982.666629 depth/1341847982.666629.png
1341847982.698638 rgb/1341847982.698638.png 1341847982.698652 depth/1341847982.698652.png
1341847982.730674 rgb/1341847982.730674.png 1341847982.731415 depth/1341847982.731415.png
1341847982.766706 rgb/1341847982.766706.png 1341847982.766748 depth/1341847982.766748.png
1341847982.798737 rgb/1341847982.798737.png 1341847982.798982 depth/1341847982.798982.png
1341847982.834747 rgb/1341847982.834747.png 1341847982.834818 depth/1341847982.834818.png
1341847982.866670 rgb/1341847982.866670.png 1341847982.866706 depth/1341847982.866706.png
1341847982.898700 rgb/1341847982.898700.png 1341847982.898764 depth/1341847982.898764.png
1341847982.934803 rgb/1341847982.934803.png 1341847982.934825 depth/1341847982.934825.png
1341847982.966708 rgb/1341847982.966708.png 1341847982.966733 depth/1341847982.966733.png
1341847982.998783 rgb/1341847982.998783.png 1341847982.998830 depth/1341847982.998830.png
1341847983.034693 rgb/1341847983.034693.png 1341847983.034747 depth/1341847983.034747.png
1341847983.066707 rgb/1341847983.066707.png 1341847983.066757 depth/1341847983.066757.png
1341847983.102757 rgb/1341847983.102757.png 1341847983.102773 depth/1341847983.102773.png
1341847983.134717 rgb/1341847983.134717.png 1341847983.134819 depth/1341847983.134819.png
1341847983.166651 rgb/1341847983.166651.png 1341847983.166667 depth/1341847983.166667.png
1341847983.202653 rgb/1341847983.202653.png 1341847983.202670 depth/1341847983.202670.png
1341847983.234717 rgb/1341847983.234717.png 1341847983.235241 depth/1341847983.235241.png
1341847983.266753 rgb/1341847983.266753.png 1341847983.266928 depth/1341847983.266928.png
1341847983.302701 rgb/1341847983.302701.png 1341847983.302721 depth/1341847983.302721.png
1341847983.334718 rgb/1341847983.334718.png 1341847983.334745 depth/1341847983.334745.png
1341847983.370887 rgb/1341847983.370887.png 1341847983.370946 depth/1341847983.370946.png
1341847983.402670 rgb/1341847983.402670.png 1341847983.402685 depth/1341847983.402685.png
1341847983.434705 rgb/1341847983.434705.png 1341847983.434724 depth/1341847983.434724.png
1341847983.470674 rgb/1341847983.470674.png 1341847983.470687 depth/1341847983.470687.png
1341847983.502767 rgb/1341847983.502767.png 1341847983.502784 depth/1341847983.502784.png
1341847983.534806 rgb/1341847983.534806.png 1341847983.535375 depth/1341847983.535375.png
1341847983.570684 rgb/1341847983.570684.png 1341847983.570707 depth/1341847983.570707.png
1341847983.602741 rgb/1341847983.602741.png 1341847983.602750 depth/1341847983.602750.png
1341847983.638729 rgb/1341847983.638729.png 1341847983.638747 depth/1341847983.638747.png
1341847983.702857 rgb/1341847983.702857.png 1341847983.702880 depth/1341847983.702880.png
1341847983.738736 rgb/1341847983.738736.png 1341847983.738756 depth/1341847983.738756.png
1341847983.770707 rgb/1341847983.770707.png 1341847983.770716 depth/1341847983.770716.png
1341847983.806672 rgb/1341847983.806672.png 1341847983.806687 depth/1341847983.806687.png
1341847983.838719 rgb/1341847983.838719.png 1341847983.838762 depth/1341847983.838762.png
1341847983.870712 rgb/1341847983.870712.png 1341847983.870739 depth/1341847983.870739.png
1341847983.906692 rgb/1341847983.906692.png 1341847983.906718 depth/1341847983.906718.png
1341847983.938757 rgb/1341847983.938757.png 1341847983.938781 depth/1341847983.938781.png
1341847983.970809 rgb/1341847983.970809.png 1341847983.971345 depth/1341847983.971345.png
1341847984.006722 rgb/1341847984.006722.png 1341847984.006741 depth/1341847984.006741.png
1341847984.038718 rgb/1341847984.038718.png 1341847984.038747 depth/1341847984.038747.png
1341847984.074737 rgb/1341847984.074737.png 1341847984.074751 depth/1341847984.074751.png
1341847984.106759 rgb/1341847984.106759.png 1341847984.106788 depth/1341847984.106788.png
1341847984.138698 rgb/1341847984.138698.png 1341847984.138713 depth/1341847984.138713.png
1341847984.174831 rgb/1341847984.174831.png 1341847984.174870 depth/1341847984.174870.png
1341847984.206711 rgb/1341847984.206711.png 1341847984.206723 depth/1341847984.206723.png
1341847984.238670 rgb/1341847984.238670.png 1341847984.238681 depth/1341847984.238681.png
1341847984.274795 rgb/1341847984.274795.png 1341847984.274814 depth/1341847984.274814.png
1341847984.306662 rgb/1341847984.306662.png 1341847984.306728 depth/1341847984.306728.png
1341847984.343094 rgb/1341847984.343094.png 1341847984.343117 depth/1341847984.343117.png
1341847984.406718 rgb/1341847984.406718.png 1341847984.406738 depth/1341847984.406738.png
1341847984.442894 rgb/1341847984.442894.png 1341847984.443623 depth/1341847984.443623.png
1341847984.474640 rgb/1341847984.474640.png 1341847984.474678 depth/1341847984.474678.png
1341847984.506747 rgb/1341847984.506747.png 1341847984.506771 depth/1341847984.506771.png
1341847984.542747 rgb/1341847984.542747.png 1341847984.542793 depth/1341847984.542793.png
1341847984.574807 rgb/1341847984.574807.png 1341847984.574826 depth/1341847984.574826.png
1341847984.610792 rgb/1341847984.610792.png 1341847984.611288 depth/1341847984.611288.png
1341847984.642667 rgb/1341847984.642667.png 1341847984.642687 depth/1341847984.642687.png
1341847984.674804 rgb/1341847984.674804.png 1341847984.674831 depth/1341847984.674831.png
1341847984.710651 rgb/1341847984.710651.png 1341847984.710661 depth/1341847984.710661.png
1341847984.743352 rgb/1341847984.743352.png 1341847984.743366 depth/1341847984.743366.png
1341847984.778881 rgb/1341847984.778881.png 1341847984.778893 depth/1341847984.778893.png
1341847984.810639 rgb/1341847984.810639.png 1341847984.810686 depth/1341847984.810686.png
1341847984.842655 rgb/1341847984.842655.png 1341847984.842727 depth/1341847984.842727.png
1341847984.878779 rgb/1341847984.878779.png 1341847984.878804 depth/1341847984.878804.png
1341847984.910613 rgb/1341847984.910613.png 1341847984.910638 depth/1341847984.910638.png
1341847984.943053 rgb/1341847984.943053.png 1341847984.943074 depth/1341847984.943074.png
1341847984.979236 rgb/1341847984.979236.png 1341847984.979255 depth/1341847984.979255.png
1341847985.010633 rgb/1341847985.010633.png 1341847985.010645 depth/1341847985.010645.png
1341847985.046612 rgb/1341847985.046612.png 1341847985.046651 depth/1341847985.046651.png
1341847985.078667 rgb/1341847985.078667.png 1341847985.078715 depth/1341847985.078715.png
1341847985.110771 rgb/1341847985.110771.png 1341847985.110785 depth/1341847985.110785.png
1341847985.146824 rgb/1341847985.146824.png 1341847985.146837 depth/1341847985.146837.png
1341847985.178699 rgb/1341847985.178699.png 1341847985.178715 depth/1341847985.178715.png
1341847985.210840 rgb/1341847985.210840.png 1341847985.210881 depth/1341847985.210881.png
1341847985.246735 rgb/1341847985.246735.png 1341847985.246755 depth/1341847985.246755.png
1341847985.278902 rgb/1341847985.278902.png 1341847985.279393 depth/1341847985.279393.png
1341847985.314648 rgb/1341847985.314648.png 1341847985.314667 depth/1341847985.314667.png
1341847985.346842 rgb/1341847985.346842.png 1341847985.347567 depth/1341847985.347567.png
1341847985.378830 rgb/1341847985.378830.png 1341847985.379393 depth/1341847985.379393.png
1341847985.414650 rgb/1341847985.414650.png 1341847985.414665 depth/1341847985.414665.png
1341847985.446854 rgb/1341847985.446854.png 1341847985.446867 depth/1341847985.446867.png
1341847985.478685 rgb/1341847985.478685.png 1341847985.478701 depth/1341847985.478701.png
1341847985.514673 rgb/1341847985.514673.png 1341847985.515080 depth/1341847985.515080.png
1341847985.546814 rgb/1341847985.546814.png 1341847985.547228 depth/1341847985.547228.png
1341847985.582581 rgb/1341847985.582581.png 1341847985.582613 depth/1341847985.582613.png
1341847985.614773 rgb/1341847985.614773.png 1341847985.614794 depth/1341847985.614794.png
1341847985.647097 rgb/1341847985.647097.png 1341847985.647135 depth/1341847985.647135.png
1341847985.682842 rgb/1341847985.682842.png 1341847985.682855 depth/1341847985.682855.png
1341847985.714719 rgb/1341847985.714719.png 1341847985.714738 depth/1341847985.714738.png
1341847985.746954 rgb/1341847985.746954.png 1341847985.747012 depth/1341847985.747012.png
1341847985.782765 rgb/1341847985.782765.png 1341847985.782792 depth/1341847985.782792.png
1341847985.814703 rgb/1341847985.814703.png 1341847985.814724 depth/1341847985.814724.png
1341847985.850739 rgb/1341847985.850739.png 1341847985.850752 depth/1341847985.850752.png
1341847985.882782 rgb/1341847985.882782.png 1341847985.882825 depth/1341847985.882825.png
1341847985.914968 rgb/1341847985.914968.png 1341847985.915001 depth/1341847985.915001.png
1341847985.950751 rgb/1341847985.950751.png 1341847985.950789 depth/1341847985.950789.png
1341847985.982712 rgb/1341847985.982712.png 1341847985.983184 depth/1341847985.983184.png
1341847986.018756 rgb/1341847986.018756.png 1341847986.018774 depth/1341847986.018774.png
1341847986.051991 rgb/1341847986.051991.png 1341847986.052003 depth/1341847986.052003.png
1341847986.082612 rgb/1341847986.082612.png 1341847986.082622 depth/1341847986.082622.png
1341847986.118719 rgb/1341847986.118719.png 1341847986.118737 depth/1341847986.118737.png
1341847986.150636 rgb/1341847986.150636.png 1341847986.150649 depth/1341847986.150649.png
1341847986.182648 rgb/1341847986.182648.png 1341847986.182659 depth/1341847986.182659.png
1341847986.218674 rgb/1341847986.218674.png 1341847986.218696 depth/1341847986.218696.png
1341847986.250584 rgb/1341847986.250584.png 1341847986.250603 depth/1341847986.250603.png
1341847986.286733 rgb/1341847986.286733.png 1341847986.286745 depth/1341847986.286745.png
1341847986.326156 rgb/1341847986.326156.png 1341847986.326815 depth/1341847986.326815.png
1341847986.359210 rgb/1341847986.359210.png 1341847986.360005 depth/1341847986.360005.png
1341847986.394467 rgb/1341847986.394467.png 1341847986.395174 depth/1341847986.395174.png
1341847986.425858 rgb/1341847986.425858.png 1341847986.425890 depth/1341847986.425890.png
1341847986.457691 rgb/1341847986.457691.png 1341847986.458500 depth/1341847986.458500.png
1341847986.493735 rgb/1341847986.493735.png 1341847986.493756 depth/1341847986.493756.png
1341847986.525772 rgb/1341847986.525772.png 1341847986.525809 depth/1341847986.525809.png
1341847986.561706 rgb/1341847986.561706.png 1341847986.561718 depth/1341847986.561718.png
1341847986.593712 rgb/1341847986.593712.png 1341847986.594246 depth/1341847986.594246.png
1341847986.625740 rgb/1341847986.625740.png 1341847986.625755 depth/1341847986.625755.png
1341847986.661920 rgb/1341847986.661920.png 1341847986.662611 depth/1341847986.662611.png
1341847986.693739 rgb/1341847986.693739.png 1341847986.693835 depth/1341847986.693835.png
1341847986.725896 rgb/1341847986.725896.png 1341847986.726876 depth/1341847986.726876.png
1341847986.762616 rgb/1341847986.762616.png 1341847986.762633 depth/1341847986.762633.png
1341847986.793794 rgb/1341847986.793794.png 1341847986.793820 depth/1341847986.793820.png
1341847986.829823 rgb/1341847986.829823.png 1341847986.829832 depth/1341847986.829832.png
1341847986.886746 rgb/1341847986.886746.png 1341847986.886842 depth/1341847986.886842.png
1341847986.922699 rgb/1341847986.922699.png 1341847986.922755 depth/1341847986.922755.png
1341847986.954690 rgb/1341847986.954690.png 1341847986.954745 depth/1341847986.954745.png
1341847986.990631 rgb/1341847986.990631.png 1341847986.990660 depth/1341847986.990660.png
1341847987.022895 rgb/1341847987.022895.png 1341847987.022913 depth/1341847987.022913.png
1341847987.054629 rgb/1341847987.054629.png 1341847987.054639 depth/1341847987.054639.png
1341847987.091223 rgb/1341847987.091223.png 1341847987.091553 depth/1341847987.091553.png
1341847987.123199 rgb/1341847987.123199.png 1341847987.123270 depth/1341847987.123270.png
1341847987.190716 rgb/1341847987.190716.png 1341847987.190730 depth/1341847987.190730.png
1341847987.259261 rgb/1341847987.259261.png 1341847987.259272 depth/1341847987.259272.png
1341847987.290653 rgb/1341847987.290653.png 1341847987.291556 depth/1341847987.291556.png
1341847987.322780 rgb/1341847987.322780.png 1341847987.322841 depth/1341847987.322841.png
1341847987.390720 rgb/1341847987.390720.png 1341847987.390738 depth/1341847987.390738.png
1341847987.422820 rgb/1341847987.422820.png 1341847987.423694 depth/1341847987.423694.png
1341847987.458620 rgb/1341847987.458620.png 1341847987.458651 depth/1341847987.458651.png
1341847987.490754 rgb/1341847987.490754.png 1341847987.490783 depth/1341847987.490783.png
1341847987.526761 rgb/1341847987.526761.png 1341847987.526770 depth/1341847987.526770.png
1341847987.558679 rgb/1341847987.558679.png 1341847987.558708 depth/1341847987.558708.png
1341847987.590776 rgb/1341847987.590776.png 1341847987.590797 depth/1341847987.590797.png
1341847987.626925 rgb/1341847987.626925.png 1341847987.626940 depth/1341847987.626940.png
1341847987.658922 rgb/1341847987.658922.png 1341847987.659671 depth/1341847987.659671.png
1341847987.691638 rgb/1341847987.691638.png 1341847987.691690 depth/1341847987.691690.png
1341847987.726721 rgb/1341847987.726721.png 1341847987.726755 depth/1341847987.726755.png
1341847987.758741 rgb/1341847987.758741.png 1341847987.758755 depth/1341847987.758755.png
1341847987.794708 rgb/1341847987.794708.png 1341847987.795290 depth/1341847987.795290.png
1341847987.826748 rgb/1341847987.826748.png 1341847987.826758 depth/1341847987.826758.png
1341847987.865879 rgb/1341847987.865879.png 1341847987.865947 depth/1341847987.865947.png
1341847987.897796 rgb/1341847987.897796.png 1341847987.897811 depth/1341847987.897811.png
1341847987.933722 rgb/1341847987.933722.png 1341847987.933810 depth/1341847987.933810.png
1341847987.965806 rgb/1341847987.965806.png 1341847987.965906 depth/1341847987.965906.png
1341847987.997794 rgb/1341847987.997794.png 1341847987.997809 depth/1341847987.997809.png
1341847988.033757 rgb/1341847988.033757.png 1341847988.033804 depth/1341847988.033804.png
1341847988.065746 rgb/1341847988.065746.png 1341847988.066172 depth/1341847988.066172.png
1341847988.098165 rgb/1341847988.098165.png 1341847988.098177 depth/1341847988.098177.png
1341847988.133763 rgb/1341847988.133763.png 1341847988.133778 depth/1341847988.133778.png
1341847988.165801 rgb/1341847988.165801.png 1341847988.165826 depth/1341847988.165826.png
1341847988.201710 rgb/1341847988.201710.png 1341847988.201741 depth/1341847988.201741.png
1341847988.233777 rgb/1341847988.233777.png 1341847988.233789 depth/1341847988.233789.png
1341847988.265702 rgb/1341847988.265702.png 1341847988.265717 depth/1341847988.265717.png
1341847988.301776 rgb/1341847988.301776.png 1341847988.301805 depth/1341847988.301805.png
1341847988.333739 rgb/1341847988.333739.png 1341847988.333771 depth/1341847988.333771.png
1341847988.369715 rgb/1341847988.369715.png 1341847988.369734 depth/1341847988.369734.png
1341847988.401745 rgb/1341847988.401745.png 1341847988.401770 depth/1341847988.401770.png
1341847988.433996 rgb/1341847988.433996.png 1341847988.434023 depth/1341847988.434023.png
1341847988.469742 rgb/1341847988.469742.png 1341847988.469802 depth/1341847988.469802.png
1341847988.502496 rgb/1341847988.502496.png 1341847988.502545 depth/1341847988.502545.png
1341847988.537778 rgb/1341847988.537778.png 1341847988.537793 depth/1341847988.537793.png
1341847988.569700 rgb/1341847988.569700.png 1341847988.569710 depth/1341847988.569710.png
1341847988.601796 rgb/1341847988.601796.png 1341847988.601811 depth/1341847988.601811.png
1341847988.637768 rgb/1341847988.637768.png 1341847988.637776 depth/1341847988.637776.png
1341847988.669807 rgb/1341847988.669807.png 1341847988.669832 depth/1341847988.669832.png
1341847988.706192 rgb/1341847988.706192.png 1341847988.706208 depth/1341847988.706208.png
1341847988.737940 rgb/1341847988.737940.png 1341847988.737953 depth/1341847988.737953.png
1341847988.769740 rgb/1341847988.769740.png 1341847988.769758 depth/1341847988.769758.png
1341847988.806051 rgb/1341847988.806051.png 1341847988.806076 depth/1341847988.806076.png
1341847988.837897 rgb/1341847988.837897.png 1341847988.837915 depth/1341847988.837915.png
1341847988.873917 rgb/1341847988.873917.png 1341847988.873942 depth/1341847988.873942.png
1341847988.937824 rgb/1341847988.937824.png 1341847988.937882 depth/1341847988.937882.png
1341847988.998737 rgb/1341847988.998737.png 1341847988.998765 depth/1341847988.998765.png
1341847989.034678 rgb/1341847989.034678.png 1341847989.034698 depth/1341847989.034698.png
1341847989.066658 rgb/1341847989.066658.png 1341847989.066676 depth/1341847989.066676.png
1341847989.098821 rgb/1341847989.098821.png 1341847989.099249 depth/1341847989.099249.png
1341847989.134676 rgb/1341847989.134676.png 1341847989.134698 depth/1341847989.134698.png
1341847989.166672 rgb/1341847989.166672.png 1341847989.166691 depth/1341847989.166691.png
1341847989.202743 rgb/1341847989.202743.png 1341847989.202772 depth/1341847989.202772.png
1341847989.234728 rgb/1341847989.234728.png 1341847989.234770 depth/1341847989.234770.png
1341847989.266651 rgb/1341847989.266651.png 1341847989.266663 depth/1341847989.266663.png
1341847989.302773 rgb/1341847989.302773.png 1341847989.302804 depth/1341847989.302804.png
1341847989.334871 rgb/1341847989.334871.png 1341847989.334903 depth/1341847989.334903.png
1341847989.366685 rgb/1341847989.366685.png 1341847989.366730 depth/1341847989.366730.png
1341847989.402777 rgb/1341847989.402777.png 1341847989.402790 depth/1341847989.402790.png
1341847989.434824 rgb/1341847989.434824.png 1341847989.434864 depth/1341847989.434864.png
1341847989.470712 rgb/1341847989.470712.png 1341847989.470743 depth/1341847989.470743.png
1341847989.502614 rgb/1341847989.502614.png 1341847989.502627 depth/1341847989.502627.png
1341847989.534687 rgb/1341847989.534687.png 1341847989.534720 depth/1341847989.534720.png
1341847989.570705 rgb/1341847989.570705.png 1341847989.570732 depth/1341847989.570732.png
1341847989.602804 rgb/1341847989.602804.png 1341847989.603280 depth/1341847989.603280.png
1341847989.634745 rgb/1341847989.634745.png 1341847989.634762 depth/1341847989.634762.png
1341847989.670627 rgb/1341847989.670627.png 1341847989.670637 depth/1341847989.670637.png
1341847989.702606 rgb/1341847989.702606.png 1341847989.702641 depth/1341847989.702641.png
1341847989.738929 rgb/1341847989.738929.png 1341847989.739046 depth/1341847989.739046.png
1341847989.770735 rgb/1341847989.770735.png 1341847989.770752 depth/1341847989.770752.png
1341847989.802890 rgb/1341847989.802890.png 1341847989.802917 depth/1341847989.802917.png
1341847989.838780 rgb/1341847989.838780.png 1341847989.838797 depth/1341847989.838797.png
1341847989.870960 rgb/1341847989.870960.png 1341847989.870960 depth/1341847989.870960.png
1341847989.902718 rgb/1341847989.902718.png 1341847989.902737 depth/1341847989.902737.png
1341847989.938921 rgb/1341847989.938921.png 1341847989.939021 depth/1341847989.939021.png
1341847989.970730 rgb/1341847989.970730.png 1341847989.970757 depth/1341847989.970757.png
1341847990.006923 rgb/1341847990.006923.png 1341847990.006941 depth/1341847990.006941.png
1341847990.039001 rgb/1341847990.039001.png 1341847990.039022 depth/1341847990.039022.png
1341847990.070686 rgb/1341847990.070686.png 1341847990.070724 depth/1341847990.070724.png
1341847990.106701 rgb/1341847990.106701.png 1341847990.106746 depth/1341847990.106746.png
1341847990.139194 rgb/1341847990.139194.png 1341847990.139215 depth/1341847990.139215.png
1341847990.171055 rgb/1341847990.171055.png 1341847990.171115 depth/1341847990.171115.png
1341847990.207022 rgb/1341847990.207022.png 1341847990.207058 depth/1341847990.207058.png
1341847990.238920 rgb/1341847990.238920.png 1341847990.238939 depth/1341847990.238939.png
1341847990.274709 rgb/1341847990.274709.png 1341847990.274725 depth/1341847990.274725.png
1341847990.306743 rgb/1341847990.306743.png 1341847990.307302 depth/1341847990.307302.png
1341847990.339079 rgb/1341847990.339079.png 1341847990.339128 depth/1341847990.339128.png
1341847990.374663 rgb/1341847990.374663.png 1341847990.374681 depth/1341847990.374681.png
1341847990.406760 rgb/1341847990.406760.png 1341847990.407262 depth/1341847990.407262.png
1341847990.442575 rgb/1341847990.442575.png 1341847990.442590 depth/1341847990.442590.png
1341847990.474644 rgb/1341847990.474644.png 1341847990.474662 depth/1341847990.474662.png
1341847990.506783 rgb/1341847990.506783.png 1341847990.506835 depth/1341847990.506835.png
1341847990.542835 rgb/1341847990.542835.png 1341847990.542844 depth/1341847990.542844.png
1341847990.574711 rgb/1341847990.574711.png 1341847990.574721 depth/1341847990.574721.png
1341847990.642783 rgb/1341847990.642783.png 1341847990.642801 depth/1341847990.642801.png
1341847990.674787 rgb/1341847990.674787.png 1341847990.674803 depth/1341847990.674803.png
1341847990.710795 rgb/1341847990.710795.png 1341847990.711535 depth/1341847990.711535.png
1341847990.742712 rgb/1341847990.742712.png 1341847990.742736 depth/1341847990.742736.png
1341847990.774671 rgb/1341847990.774671.png 1341847990.774681 depth/1341847990.774681.png
1341847990.810771 rgb/1341847990.810771.png 1341847990.810817 depth/1341847990.810817.png
1341847990.842713 rgb/1341847990.842713.png 1341847990.842732 depth/1341847990.842732.png
1341847990.874745 rgb/1341847990.874745.png 1341847990.874776 depth/1341847990.874776.png
1341847990.910825 rgb/1341847990.910825.png 1341847990.910852 depth/1341847990.910852.png
1341847990.942685 rgb/1341847990.942685.png 1341847990.942701 depth/1341847990.942701.png
1341847990.978824 rgb/1341847990.978824.png 1341847990.978843 depth/1341847990.978843.png
1341847991.010797 rgb/1341847991.010797.png 1341847991.011241 depth/1341847991.011241.png
1341847991.042752 rgb/1341847991.042752.png 1341847991.042762 depth/1341847991.042762.png
1341847991.078680 rgb/1341847991.078680.png 1341847991.078699 depth/1341847991.078699.png
1341847991.111319 rgb/1341847991.111319.png 1341847991.111338 depth/1341847991.111338.png
1341847991.142784 rgb/1341847991.142784.png 1341847991.142813 depth/1341847991.142813.png
1341847991.178778 rgb/1341847991.178778.png 1341847991.178815 depth/1341847991.178815.png
1341847991.210687 rgb/1341847991.210687.png 1341847991.210701 depth/1341847991.210701.png
1341847991.246842 rgb/1341847991.246842.png 1341847991.246874 depth/1341847991.246874.png
1341847991.278726 rgb/1341847991.278726.png 1341847991.278763 depth/1341847991.278763.png
1341847991.310807 rgb/1341847991.310807.png 1341847991.310849 depth/1341847991.310849.png
1341847991.346722 rgb/1341847991.346722.png 1341847991.346739 depth/1341847991.346739.png
1341847991.378800 rgb/1341847991.378800.png 1341847991.378827 depth/1341847991.378827.png
1341847991.414715 rgb/1341847991.414715.png 1341847991.414740 depth/1341847991.414740.png
1341847991.446744 rgb/1341847991.446744.png 1341847991.446753 depth/1341847991.446753.png
1341847991.478824 rgb/1341847991.478824.png 1341847991.478846 depth/1341847991.478846.png
1341847991.514709 rgb/1341847991.514709.png 1341847991.514730 depth/1341847991.514730.png
1341847991.546725 rgb/1341847991.546725.png 1341847991.546739 depth/1341847991.546739.png
1341847991.578804 rgb/1341847991.578804.png 1341847991.578924 depth/1341847991.578924.png
1341847991.614853 rgb/1341847991.614853.png 1341847991.614880 depth/1341847991.614880.png
1341847991.646714 rgb/1341847991.646714.png 1341847991.646733 depth/1341847991.646733.png
1341847991.689872 rgb/1341847991.689872.png 1341847991.689946 depth/1341847991.689946.png
1341847991.746823 rgb/1341847991.746823.png 1341847991.746844 depth/1341847991.746844.png
1341847991.782657 rgb/1341847991.782657.png 1341847991.782683 depth/1341847991.782683.png
1341847991.814748 rgb/1341847991.814748.png 1341847991.814763 depth/1341847991.814763.png
1341847991.846729 rgb/1341847991.846729.png 1341847991.846745 depth/1341847991.846745.png
1341847991.882784 rgb/1341847991.882784.png 1341847991.882794 depth/1341847991.882794.png
1341847991.915817 rgb/1341847991.915817.png 1341847991.915861 depth/1341847991.915861.png
1341847991.950761 rgb/1341847991.950761.png 1341847991.951013 depth/1341847991.951013.png
1341847991.982826 rgb/1341847991.982826.png 1341847991.982873 depth/1341847991.982873.png
1341847992.014724 rgb/1341847992.014724.png 1341847992.014777 depth/1341847992.014777.png
1341847992.050647 rgb/1341847992.050647.png 1341847992.050662 depth/1341847992.050662.png
1341847992.082793 rgb/1341847992.082793.png 1341847992.082807 depth/1341847992.082807.png
1341847992.114842 rgb/1341847992.114842.png 1341847992.114861 depth/1341847992.114861.png
1341847992.150789 rgb/1341847992.150789.png 1341847992.150826 depth/1341847992.150826.png
1341847992.182813 rgb/1341847992.182813.png 1341847992.182830 depth/1341847992.182830.png
1341847992.218736 rgb/1341847992.218736.png 1341847992.218794 depth/1341847992.218794.png
1341847992.250652 rgb/1341847992.250652.png 1341847992.250777 depth/1341847992.250777.png
1341847992.318683 rgb/1341847992.318683.png 1341847992.318697 depth/1341847992.318697.png
1341847992.350695 rgb/1341847992.350695.png 1341847992.350709 depth/1341847992.350709.png
1341847992.382858 rgb/1341847992.382858.png 1341847992.382868 depth/1341847992.382868.png
1341847992.418855 rgb/1341847992.418855.png 1341847992.418869 depth/1341847992.418869.png
1341847992.450822 rgb/1341847992.450822.png 1341847992.450837 depth/1341847992.450837.png
1341847992.486713 rgb/1341847992.486713.png 1341847992.487395 depth/1341847992.487395.png
1341847992.518735 rgb/1341847992.518735.png 1341847992.518771 depth/1341847992.518771.png
1341847992.550596 rgb/1341847992.550596.png 1341847992.550630 depth/1341847992.550630.png
1341847992.586730 rgb/1341847992.586730.png 1341847992.586755 depth/1341847992.586755.png
1341847992.618832 rgb/1341847992.618832.png 1341847992.618846 depth/1341847992.618846.png
1341847992.654692 rgb/1341847992.654692.png 1341847992.654748 depth/1341847992.654748.png
1341847992.686829 rgb/1341847992.686829.png 1341847992.686855 depth/1341847992.686855.png
1341847992.718718 rgb/1341847992.718718.png 1341847992.718740 depth/1341847992.718740.png
1341847992.754765 rgb/1341847992.754765.png 1341847992.754788 depth/1341847992.754788.png
1341847992.786631 rgb/1341847992.786631.png 1341847992.786663 depth/1341847992.786663.png
1341847992.818723 rgb/1341847992.818723.png 1341847992.818748 depth/1341847992.818748.png
1341847992.854856 rgb/1341847992.854856.png 1341847992.854878 depth/1341847992.854878.png
1341847992.886610 rgb/1341847992.886610.png 1341847992.886642 depth/1341847992.886642.png
1341847992.922713 rgb/1341847992.922713.png 1341847992.922733 depth/1341847992.922733.png
1341847992.954645 rgb/1341847992.954645.png 1341847992.955395 depth/1341847992.955395.png
1341847992.986720 rgb/1341847992.986720.png 1341847992.986737 depth/1341847992.986737.png
1341847993.022736 rgb/1341847993.022736.png 1341847993.022781 depth/1341847993.022781.png
1341847993.054757 rgb/1341847993.054757.png 1341847993.054770 depth/1341847993.054770.png
1341847993.086751 rgb/1341847993.086751.png 1341847993.086778 depth/1341847993.086778.png
1341847993.122668 rgb/1341847993.122668.png 1341847993.122697 depth/1341847993.122697.png
1341847993.154688 rgb/1341847993.154688.png 1341847993.154697 depth/1341847993.154697.png
1341847993.190779 rgb/1341847993.190779.png 1341847993.190813 depth/1341847993.190813.png
1341847993.222703 rgb/1341847993.222703.png 1341847993.222720 depth/1341847993.222720.png
1341847993.261799 rgb/1341847993.261799.png 1341847993.261866 depth/1341847993.261866.png
1341847993.322794 rgb/1341847993.322794.png 1341847993.322820 depth/1341847993.322820.png
1341847993.354702 rgb/1341847993.354702.png 1341847993.354727 depth/1341847993.354727.png
1341847993.390722 rgb/1341847993.390722.png 1341847993.391295 depth/1341847993.391295.png
1341847993.422745 rgb/1341847993.422745.png 1341847993.422772 depth/1341847993.422772.png
1341847993.458848 rgb/1341847993.458848.png 1341847993.458981 depth/1341847993.458981.png
1341847993.490680 rgb/1341847993.490680.png 1341847993.490694 depth/1341847993.490694.png
1341847993.522707 rgb/1341847993.522707.png 1341847993.522726 depth/1341847993.522726.png
1341847993.558719 rgb/1341847993.558719.png 1341847993.558743 depth/1341847993.558743.png
1341847993.590981 rgb/1341847993.590981.png 1341847993.591005 depth/1341847993.591005.png
1341847993.626764 rgb/1341847993.626764.png 1341847993.626777 depth/1341847993.626777.png
1341847993.658928 rgb/1341847993.658928.png 1341847993.658977 depth/1341847993.658977.png
1341847993.690739 rgb/1341847993.690739.png 1341847993.691246 depth/1341847993.691246.png
1341847993.727062 rgb/1341847993.727062.png 1341847993.727881 depth/1341847993.727881.png
1341847993.790887 rgb/1341847993.790887.png 1341847993.791002 depth/1341847993.791002.png
1341847993.826735 rgb/1341847993.826735.png 1341847993.826846 depth/1341847993.826846.png
1341847993.858891 rgb/1341847993.858891.png 1341847993.858904 depth/1341847993.858904.png
1341847993.901726 rgb/1341847993.901726.png 1341847993.902671 depth/1341847993.902671.png
1341847993.933661 rgb/1341847993.933661.png 1341847993.933692 depth/1341847993.933692.png
1341847993.965821 rgb/1341847993.965821.png 1341847993.965832 depth/1341847993.965832.png
1341847994.001991 rgb/1341847994.001991.png 1341847994.002756 depth/1341847994.002756.png
1341847994.034008 rgb/1341847994.034008.png 1341847994.034124 depth/1341847994.034124.png
1341847994.065706 rgb/1341847994.065706.png 1341847994.065765 depth/1341847994.065765.png
1341847994.101772 rgb/1341847994.101772.png 1341847994.101785 depth/1341847994.101785.png
1341847994.133885 rgb/1341847994.133885.png 1341847994.133915 depth/1341847994.133915.png
1341847994.169705 rgb/1341847994.169705.png 1341847994.169723 depth/1341847994.169723.png
1341847994.201675 rgb/1341847994.201675.png 1341847994.201710 depth/1341847994.201710.png
1341847994.233618 rgb/1341847994.233618.png 1341847994.233648 depth/1341847994.233648.png
1341847994.269680 rgb/1341847994.269680.png 1341847994.269699 depth/1341847994.269699.png
1341847994.301751 rgb/1341847994.301751.png 1341847994.301791 depth/1341847994.301791.png
1341847994.333755 rgb/1341847994.333755.png 1341847994.333773 depth/1341847994.333773.png
1341847994.369712 rgb/1341847994.369712.png 1341847994.369729 depth/1341847994.369729.png
1341847994.401655 rgb/1341847994.401655.png 1341847994.401681 depth/1341847994.401681.png
1341847994.433802 rgb/1341847994.433802.png 1341847994.434241 depth/1341847994.434241.png
1341847994.469690 rgb/1341847994.469690.png 1341847994.469702 depth/1341847994.469702.png
1341847994.501736 rgb/1341847994.501736.png 1341847994.501770 depth/1341847994.501770.png
1341847994.537738 rgb/1341847994.537738.png 1341847994.537760 depth/1341847994.537760.png
1341847994.569734 rgb/1341847994.569734.png 1341847994.570212 depth/1341847994.570212.png
1341847994.601688 rgb/1341847994.601688.png 1341847994.601735 depth/1341847994.601735.png
1341847994.637836 rgb/1341847994.637836.png 1341847994.637851 depth/1341847994.637851.png
1341847994.669750 rgb/1341847994.669750.png 1341847994.669907 depth/1341847994.669907.png
1341847994.701643 rgb/1341847994.701643.png 1341847994.701657 depth/1341847994.701657.png
1341847994.769803 rgb/1341847994.769803.png 1341847994.769892 depth/1341847994.769892.png
1341847994.831306 rgb/1341847994.831306.png 1341847994.831318 depth/1341847994.831318.png
1341847994.866828 rgb/1341847994.866828.png 1341847994.866892 depth/1341847994.866892.png
1341847994.898727 rgb/1341847994.898727.png 1341847994.898740 depth/1341847994.898740.png
1341847994.930711 rgb/1341847994.930711.png 1341847994.930781 depth/1341847994.930781.png
1341847994.966673 rgb/1341847994.966673.png 1341847994.966794 depth/1341847994.966794.png
1341847994.998679 rgb/1341847994.998679.png 1341847994.998726 depth/1341847994.998726.png
1341847995.030768 rgb/1341847995.030768.png 1341847995.030829 depth/1341847995.030829.png
1341847995.066673 rgb/1341847995.066673.png 1341847995.066736 depth/1341847995.066736.png
1341847995.098711 rgb/1341847995.098711.png 1341847995.098802 depth/1341847995.098802.png
1341847995.134939 rgb/1341847995.134939.png 1341847995.134968 depth/1341847995.134968.png
1341847995.166644 rgb/1341847995.166644.png 1341847995.166683 depth/1341847995.166683.png
1341847995.198787 rgb/1341847995.198787.png 1341847995.198800 depth/1341847995.198800.png
1341847995.234663 rgb/1341847995.234663.png 1341847995.234690 depth/1341847995.234690.png
1341847995.266776 rgb/1341847995.266776.png 1341847995.266841 depth/1341847995.266841.png
1341847995.298812 rgb/1341847995.298812.png 1341847995.298807 depth/1341847995.298807.png
1341847995.334686 rgb/1341847995.334686.png 1341847995.334708 depth/1341847995.334708.png
1341847995.366701 rgb/1341847995.366701.png 1341847995.366716 depth/1341847995.366716.png
1341847995.402793 rgb/1341847995.402793.png 1341847995.402804 depth/1341847995.402804.png
1341847995.434743 rgb/1341847995.434743.png 1341847995.434769 depth/1341847995.434769.png
1341847995.466776 rgb/1341847995.466776.png 1341847995.466791 depth/1341847995.466791.png
1341847995.502702 rgb/1341847995.502702.png 1341847995.502726 depth/1341847995.502726.png
1341847995.534752 rgb/1341847995.534752.png 1341847995.534803 depth/1341847995.534803.png
1341847995.566681 rgb/1341847995.566681.png 1341847995.566696 depth/1341847995.566696.png
1341847995.602698 rgb/1341847995.602698.png 1341847995.602714 depth/1341847995.602714.png
1341847995.634814 rgb/1341847995.634814.png 1341847995.634845 depth/1341847995.634845.png
1341847995.670769 rgb/1341847995.670769.png 1341847995.670798 depth/1341847995.670798.png
1341847995.702780 rgb/1341847995.702780.png 1341847995.702795 depth/1341847995.702795.png
1341847995.734774 rgb/1341847995.734774.png 1341847995.734786 depth/1341847995.734786.png
1341847995.770704 rgb/1341847995.770704.png 1341847995.770716 depth/1341847995.770716.png
1341847995.802752 rgb/1341847995.802752.png 1341847995.802771 depth/1341847995.802771.png
1341847995.838779 rgb/1341847995.838779.png 1341847995.838812 depth/1341847995.838812.png
1341847995.870641 rgb/1341847995.870641.png 1341847995.870667 depth/1341847995.870667.png
1341847995.902803 rgb/1341847995.902803.png 1341847995.902829 depth/1341847995.902829.png
1341847995.938733 rgb/1341847995.938733.png 1341847995.938742 depth/1341847995.938742.png
1341847995.970733 rgb/1341847995.970733.png 1341847995.970762 depth/1341847995.970762.png
1341847996.002709 rgb/1341847996.002709.png 1341847996.002725 depth/1341847996.002725.png
1341847996.038762 rgb/1341847996.038762.png 1341847996.038793 depth/1341847996.038793.png
1341847996.070721 rgb/1341847996.070721.png 1341847996.070742 depth/1341847996.070742.png
1341847996.106729 rgb/1341847996.106729.png 1341847996.106752 depth/1341847996.106752.png
1341847996.138845 rgb/1341847996.138845.png 1341847996.138877 depth/1341847996.138877.png
1341847996.170714 rgb/1341847996.170714.png 1341847996.170740 depth/1341847996.170740.png
1341847996.206643 rgb/1341847996.206643.png 1341847996.206677 depth/1341847996.206677.png
1341847996.239003 rgb/1341847996.239003.png 1341847996.239037 depth/1341847996.239037.png
1341847996.270754 rgb/1341847996.270754.png 1341847996.270779 depth/1341847996.270779.png
1341847996.338944 rgb/1341847996.338944.png 1341847996.338989 depth/1341847996.338989.png
1341847996.374711 rgb/1341847996.374711.png 1341847996.374732 depth/1341847996.374732.png
1341847996.406705 rgb/1341847996.406705.png 1341847996.406731 depth/1341847996.406731.png
1341847996.438632 rgb/1341847996.438632.png 1341847996.438706 depth/1341847996.438706.png
1341847996.474783 rgb/1341847996.474783.png 1341847996.474837 depth/1341847996.474837.png
1341847996.506707 rgb/1341847996.506707.png 1341847996.506720 depth/1341847996.506720.png
1341847996.538771 rgb/1341847996.538771.png 1341847996.538791 depth/1341847996.538791.png
1341847996.574796 rgb/1341847996.574796.png 1341847996.574812 depth/1341847996.574812.png
1341847996.607104 rgb/1341847996.607104.png 1341847996.607158 depth/1341847996.607158.png
1341847996.642752 rgb/1341847996.642752.png 1341847996.642767 depth/1341847996.642767.png
1341847996.674774 rgb/1341847996.674774.png 1341847996.674789 depth/1341847996.674789.png
1341847996.706896 rgb/1341847996.706896.png 1341847996.706910 depth/1341847996.706910.png
1341847996.742663 rgb/1341847996.742663.png 1341847996.742685 depth/1341847996.742685.png
1341847996.774747 rgb/1341847996.774747.png 1341847996.774759 depth/1341847996.774759.png
1341847996.806787 rgb/1341847996.806787.png 1341847996.806842 depth/1341847996.806842.png
1341847996.842763 rgb/1341847996.842763.png 1341847996.842787 depth/1341847996.842787.png
1341847996.874766 rgb/1341847996.874766.png 1341847996.874793 depth/1341847996.874793.png
1341847996.910785 rgb/1341847996.910785.png 1341847996.911011 depth/1341847996.911011.png
1341847996.942686 rgb/1341847996.942686.png 1341847996.943167 depth/1341847996.943167.png
1341847996.974782 rgb/1341847996.974782.png 1341847996.974796 depth/1341847996.974796.png
1341847997.010744 rgb/1341847997.010744.png 1341847997.010766 depth/1341847997.010766.png
1341847997.042675 rgb/1341847997.042675.png 1341847997.042684 depth/1341847997.042684.png
1341847997.078725 rgb/1341847997.078725.png 1341847997.078744 depth/1341847997.078744.png
1341847997.142993 rgb/1341847997.142993.png 1341847997.143035 depth/1341847997.143035.png
1341847997.178794 rgb/1341847997.178794.png 1341847997.178824 depth/1341847997.178824.png
1341847997.210888 rgb/1341847997.210888.png 1341847997.210908 depth/1341847997.210908.png
1341847997.242959 rgb/1341847997.242959.png 1341847997.242983 depth/1341847997.242983.png
1341847997.278756 rgb/1341847997.278756.png 1341847997.279364 depth/1341847997.279364.png
1341847997.311412 rgb/1341847997.311412.png 1341847997.311453 depth/1341847997.311453.png
1341847997.346642 rgb/1341847997.346642.png 1341847997.346654 depth/1341847997.346654.png
1341847997.378668 rgb/1341847997.378668.png 1341847997.378700 depth/1341847997.378700.png
1341847997.410817 rgb/1341847997.410817.png 1341847997.411689 depth/1341847997.411689.png
1341847997.446693 rgb/1341847997.446693.png 1341847997.446712 depth/1341847997.446712.png
1341847997.478752 rgb/1341847997.478752.png 1341847997.478763 depth/1341847997.478763.png
1341847997.510941 rgb/1341847997.510941.png 1341847997.511370 depth/1341847997.511370.png
1341847997.546599 rgb/1341847997.546599.png 1341847997.546615 depth/1341847997.546615.png
1341847997.578740 rgb/1341847997.578740.png 1341847997.578767 depth/1341847997.578767.png
1341847997.614736 rgb/1341847997.614736.png 1341847997.614761 depth/1341847997.614761.png
1341847997.646995 rgb/1341847997.646995.png 1341847997.647012 depth/1341847997.647012.png
1341847997.678842 rgb/1341847997.678842.png 1341847997.678858 depth/1341847997.678858.png
1341847997.714639 rgb/1341847997.714639.png 1341847997.714649 depth/1341847997.714649.png
1341847997.746602 rgb/1341847997.746602.png 1341847997.746633 depth/1341847997.746633.png
1341847997.778734 rgb/1341847997.778734.png 1341847997.778758 depth/1341847997.778758.png
1341847997.846906 rgb/1341847997.846906.png 1341847997.846947 depth/1341847997.846947.png
1341847997.882641 rgb/1341847997.882641.png 1341847997.883109 depth/1341847997.883109.png
1341847997.915169 rgb/1341847997.915169.png 1341847997.915187 depth/1341847997.915187.png
1341847997.946999 rgb/1341847997.946999.png 1341847997.947048 depth/1341847997.947048.png
1341847997.982715 rgb/1341847997.982715.png 1341847997.982857 depth/1341847997.982857.png
1341847998.014866 rgb/1341847998.014866.png 1341847998.014891 depth/1341847998.014891.png
1341847998.050805 rgb/1341847998.050805.png 1341847998.050878 depth/1341847998.050878.png
1341847998.082631 rgb/1341847998.082631.png 1341847998.082647 depth/1341847998.082647.png
1341847998.122275 rgb/1341847998.122275.png 1341847998.123265 depth/1341847998.123265.png
1341847998.154051 rgb/1341847998.154051.png 1341847998.154516 depth/1341847998.154516.png
1341847998.185663 rgb/1341847998.185663.png 1341847998.185678 depth/1341847998.185678.png
1341847998.253760 rgb/1341847998.253760.png 1341847998.253822 depth/1341847998.253822.png
1341847998.318804 rgb/1341847998.318804.png 1341847998.318825 depth/1341847998.318825.png
1341847998.351206 rgb/1341847998.351206.png 1341847998.351221 depth/1341847998.351221.png
1341847998.382723 rgb/1341847998.382723.png 1341847998.382744 depth/1341847998.382744.png
1341847998.419237 rgb/1341847998.419237.png 1341847998.419264 depth/1341847998.419264.png
1341847998.450786 rgb/1341847998.450786.png 1341847998.450814 depth/1341847998.450814.png
1341847998.484037 rgb/1341847998.484037.png 1341847998.484057 depth/1341847998.484057.png
1341847998.518722 rgb/1341847998.518722.png 1341847998.518744 depth/1341847998.518744.png
1341847998.550746 rgb/1341847998.550746.png 1341847998.550766 depth/1341847998.550766.png
1341847998.586740 rgb/1341847998.586740.png 1341847998.586754 depth/1341847998.586754.png
1341847998.618771 rgb/1341847998.618771.png 1341847998.618853 depth/1341847998.618853.png
1341847998.650736 rgb/1341847998.650736.png 1341847998.650754 depth/1341847998.650754.png
1341847998.686862 rgb/1341847998.686862.png 1341847998.686872 depth/1341847998.686872.png
1341847998.718741 rgb/1341847998.718741.png 1341847998.718754 depth/1341847998.718754.png
1341847998.750838 rgb/1341847998.750838.png 1341847998.750862 depth/1341847998.750862.png
1341847998.786762 rgb/1341847998.786762.png 1341847998.786777 depth/1341847998.786777.png
1341847998.818756 rgb/1341847998.818756.png 1341847998.818773 depth/1341847998.818773.png
1341847998.854711 rgb/1341847998.854711.png 1341847998.854733 depth/1341847998.854733.png
1341847998.886699 rgb/1341847998.886699.png 1341847998.886727 depth/1341847998.886727.png
1341847998.918666 rgb/1341847998.918666.png 1341847998.918681 depth/1341847998.918681.png
1341847998.954799 rgb/1341847998.954799.png 1341847998.954812 depth/1341847998.954812.png
1341847998.986722 rgb/1341847998.986722.png 1341847998.986738 depth/1341847998.986738.png
1341847999.018809 rgb/1341847999.018809.png 1341847999.018827 depth/1341847999.018827.png
1341847999.054894 rgb/1341847999.054894.png 1341847999.054947 depth/1341847999.054947.png
1341847999.086763 rgb/1341847999.086763.png 1341847999.086789 depth/1341847999.086789.png
1341847999.122718 rgb/1341847999.122718.png 1341847999.122734 depth/1341847999.122734.png
1341847999.154891 rgb/1341847999.154891.png 1341847999.154910 depth/1341847999.154910.png
1341847999.186738 rgb/1341847999.186738.png 1341847999.186756 depth/1341847999.186756.png
1341847999.222717 rgb/1341847999.222717.png 1341847999.222728 depth/1341847999.222728.png
1341847999.290995 rgb/1341847999.290995.png 1341847999.291097 depth/1341847999.291097.png
1341847999.322701 rgb/1341847999.322701.png 1341847999.322715 depth/1341847999.322715.png
1341847999.354861 rgb/1341847999.354861.png 1341847999.354880 depth/1341847999.354880.png
1341847999.390790 rgb/1341847999.390790.png 1341847999.390873 depth/1341847999.390873.png
1341847999.423935 rgb/1341847999.423935.png 1341847999.423953 depth/1341847999.423953.png
1341847999.454933 rgb/1341847999.454933.png 1341847999.454965 depth/1341847999.454965.png
1341847999.490878 rgb/1341847999.490878.png 1341847999.490960 depth/1341847999.490960.png
1341847999.522673 rgb/1341847999.522673.png 1341847999.522711 depth/1341847999.522711.png
1341847999.558926 rgb/1341847999.558926.png 1341847999.558949 depth/1341847999.558949.png
1341847999.590686 rgb/1341847999.590686.png 1341847999.590703 depth/1341847999.590703.png
1341847999.622896 rgb/1341847999.622896.png 1341847999.622914 depth/1341847999.622914.png
1341847999.658843 rgb/1341847999.658843.png 1341847999.658860 depth/1341847999.658860.png
1341847999.691111 rgb/1341847999.691111.png 1341847999.691169 depth/1341847999.691169.png
1341847999.722697 rgb/1341847999.722697.png 1341847999.722745 depth/1341847999.722745.png
1341847999.758778 rgb/1341847999.758778.png 1341847999.758816 depth/1341847999.758816.png
1341847999.791003 rgb/1341847999.791003.png 1341847999.791018 depth/1341847999.791018.png
1341847999.826747 rgb/1341847999.826747.png 1341847999.826760 depth/1341847999.826760.png
1341847999.858757 rgb/1341847999.858757.png 1341847999.858819 depth/1341847999.858819.png
1341847999.897730 rgb/1341847999.897730.png 1341847999.897755 depth/1341847999.897755.png
1341847999.958786 rgb/1341847999.958786.png 1341847999.958798 depth/1341847999.958798.png
1341847999.990848 rgb/1341847999.990848.png 1341847999.991017 depth/1341847999.991017.png
1341848000.026656 rgb/1341848000.026656.png 1341848000.026670 depth/1341848000.026670.png
1341848000.058724 rgb/1341848000.058724.png 1341848000.058808 depth/1341848000.058808.png
1341848000.094780 rgb/1341848000.094780.png 1341848000.094794 depth/1341848000.094794.png
1341848000.126737 rgb/1341848000.126737.png 1341848000.126804 depth/1341848000.126804.png
1341848000.158633 rgb/1341848000.158633.png 1341848000.158647 depth/1341848000.158647.png
1341848000.194808 rgb/1341848000.194808.png 1341848000.194844 depth/1341848000.194844.png
1341848000.227063 rgb/1341848000.227063.png 1341848000.228401 depth/1341848000.228401.png
1341848000.266975 rgb/1341848000.266975.png 1341848000.267040 depth/1341848000.267040.png
1341848000.327132 rgb/1341848000.327132.png 1341848000.327144 depth/1341848000.327144.png
1341848000.362696 rgb/1341848000.362696.png 1341848000.362714 depth/1341848000.362714.png
1341848000.394654 rgb/1341848000.394654.png 1341848000.394668 depth/1341848000.394668.png
1341848000.426772 rgb/1341848000.426772.png 1341848000.426894 depth/1341848000.426894.png
1341848000.462696 rgb/1341848000.462696.png 1341848000.462704 depth/1341848000.462704.png
1341848000.494711 rgb/1341848000.494711.png 1341848000.494720 depth/1341848000.494720.png
1341848000.530849 rgb/1341848000.530849.png 1341848000.530871 depth/1341848000.530871.png
1341848000.562770 rgb/1341848000.562770.png 1341848000.562803 depth/1341848000.562803.png
1341848000.594838 rgb/1341848000.594838.png 1341848000.594876 depth/1341848000.594876.png
1341848000.630641 rgb/1341848000.630641.png 1341848000.630658 depth/1341848000.630658.png
1341848000.662663 rgb/1341848000.662663.png 1341848000.662683 depth/1341848000.662683.png
1341848000.695377 rgb/1341848000.695377.png 1341848000.695394 depth/1341848000.695394.png
1341848000.730805 rgb/1341848000.730805.png 1341848000.730825 depth/1341848000.730825.png
1341848000.762655 rgb/1341848000.762655.png 1341848000.762704 depth/1341848000.762704.png
1341848000.798741 rgb/1341848000.798741.png 1341848000.798754 depth/1341848000.798754.png
1341848000.830729 rgb/1341848000.830729.png 1341848000.830744 depth/1341848000.830744.png
1341848000.862750 rgb/1341848000.862750.png 1341848000.862762 depth/1341848000.862762.png
1341848000.898723 rgb/1341848000.898723.png 1341848000.898741 depth/1341848000.898741.png
1341848000.930722 rgb/1341848000.930722.png 1341848000.930740 depth/1341848000.930740.png
1341848000.963197 rgb/1341848000.963197.png 1341848000.963623 depth/1341848000.963623.png
1341848000.998783 rgb/1341848000.998783.png 1341848000.998807 depth/1341848000.998807.png
1341848001.030740 rgb/1341848001.030740.png 1341848001.030757 depth/1341848001.030757.png
1341848001.067042 rgb/1341848001.067042.png 1341848001.067105 depth/1341848001.067105.png
1341848001.098800 rgb/1341848001.098800.png 1341848001.098830 depth/1341848001.098830.png
1341848001.130714 rgb/1341848001.130714.png 1341848001.130736 depth/1341848001.130736.png
1341848001.205951 rgb/1341848001.205951.png 1341848001.206049 depth/1341848001.206049.png
1341848001.266775 rgb/1341848001.266775.png 1341848001.266790 depth/1341848001.266790.png
1341848001.299150 rgb/1341848001.299150.png 1341848001.299167 depth/1341848001.299167.png
1341848001.334803 rgb/1341848001.334803.png 1341848001.334830 depth/1341848001.334830.png
1341848001.366701 rgb/1341848001.366701.png 1341848001.366725 depth/1341848001.366725.png
1341848001.399276 rgb/1341848001.399276.png 1341848001.399293 depth/1341848001.399293.png
1341848001.434718 rgb/1341848001.434718.png 1341848001.434760 depth/1341848001.434760.png
1341848001.466720 rgb/1341848001.466720.png 1341848001.466756 depth/1341848001.466756.png
1341848001.502686 rgb/1341848001.502686.png 1341848001.502748 depth/1341848001.502748.png
1341848001.534905 rgb/1341848001.534905.png 1341848001.535602 depth/1341848001.535602.png
1341848001.567011 rgb/1341848001.567011.png 1341848001.567686 depth/1341848001.567686.png
1341848001.602899 rgb/1341848001.602899.png 1341848001.603041 depth/1341848001.603041.png
1341848001.634657 rgb/1341848001.634657.png 1341848001.634679 depth/1341848001.634679.png
1341848001.666646 rgb/1341848001.666646.png 1341848001.666695 depth/1341848001.666695.png
1341848001.734859 rgb/1341848001.734859.png 1341848001.734874 depth/1341848001.734874.png
1341848001.770725 rgb/1341848001.770725.png 1341848001.771400 depth/1341848001.771400.png
1341848001.802763 rgb/1341848001.802763.png 1341848001.803395 depth/1341848001.803395.png
1341848001.834761 rgb/1341848001.834761.png 1341848001.834778 depth/1341848001.834778.png
1341848001.870724 rgb/1341848001.870724.png 1341848001.870742 depth/1341848001.870742.png
1341848001.902749 rgb/1341848001.902749.png 1341848001.902764 depth/1341848001.902764.png
1341848001.934732 rgb/1341848001.934732.png 1341848001.934794 depth/1341848001.934794.png
1341848001.970708 rgb/1341848001.970708.png 1341848001.970782 depth/1341848001.970782.png
1341848002.002731 rgb/1341848002.002731.png 1341848002.002752 depth/1341848002.002752.png
1341848002.038858 rgb/1341848002.038858.png 1341848002.038880 depth/1341848002.038880.png
1341848002.070767 rgb/1341848002.070767.png 1341848002.070781 depth/1341848002.070781.png
1341848002.102720 rgb/1341848002.102720.png 1341848002.102819 depth/1341848002.102819.png
1341848002.138653 rgb/1341848002.138653.png 1341848002.138667 depth/1341848002.138667.png
1341848002.171849 rgb/1341848002.171849.png 1341848002.171908 depth/1341848002.171908.png
1341848002.202698 rgb/1341848002.202698.png 1341848002.202713 depth/1341848002.202713.png
1341848002.238731 rgb/1341848002.238731.png 1341848002.238742 depth/1341848002.238742.png
1341848002.270763 rgb/1341848002.270763.png 1341848002.270780 depth/1341848002.270780.png
1341848002.306708 rgb/1341848002.306708.png 1341848002.306724 depth/1341848002.306724.png
1341848002.338850 rgb/1341848002.338850.png 1341848002.338920 depth/1341848002.338920.png
1341848002.370786 rgb/1341848002.370786.png 1341848002.371472 depth/1341848002.371472.png
1341848002.406793 rgb/1341848002.406793.png 1341848002.406802 depth/1341848002.406802.png
1341848002.438766 rgb/1341848002.438766.png 1341848002.438797 depth/1341848002.438797.png
1341848002.474697 rgb/1341848002.474697.png 1341848002.474720 depth/1341848002.474720.png
1341848002.506756 rgb/1341848002.506756.png 1341848002.506777 depth/1341848002.506777.png
1341848002.538812 rgb/1341848002.538812.png 1341848002.539346 depth/1341848002.539346.png
1341848002.574707 rgb/1341848002.574707.png 1341848002.574741 depth/1341848002.574741.png
1341848002.606780 rgb/1341848002.606780.png 1341848002.606818 depth/1341848002.606818.png
1341848002.639359 rgb/1341848002.639359.png 1341848002.639381 depth/1341848002.639381.png
1341848002.674651 rgb/1341848002.674651.png 1341848002.674664 depth/1341848002.674664.png
1341848002.713789 rgb/1341848002.713789.png 1341848002.713950 depth/1341848002.713950.png
1341848002.774760 rgb/1341848002.774760.png 1341848002.774778 depth/1341848002.774778.png
1341848002.806780 rgb/1341848002.806780.png 1341848002.806797 depth/1341848002.806797.png
1341848002.842833 rgb/1341848002.842833.png 1341848002.842854 depth/1341848002.842854.png
1341848002.875238 rgb/1341848002.875238.png 1341848002.875294 depth/1341848002.875294.png
1341848002.906656 rgb/1341848002.906656.png 1341848002.906670 depth/1341848002.906670.png
1341848002.943323 rgb/1341848002.943323.png 1341848002.943336 depth/1341848002.943336.png
1341848002.974597 rgb/1341848002.974597.png 1341848002.974617 depth/1341848002.974617.png
1341848003.010885 rgb/1341848003.010885.png 1341848003.010926 depth/1341848003.010926.png
1341848003.042638 rgb/1341848003.042638.png 1341848003.042649 depth/1341848003.042649.png
1341848003.074988 rgb/1341848003.074988.png 1341848003.075599 depth/1341848003.075599.png
1341848003.110641 rgb/1341848003.110641.png 1341848003.110659 depth/1341848003.110659.png
1341848003.142626 rgb/1341848003.142626.png 1341848003.142643 depth/1341848003.142643.png
1341848003.242926 rgb/1341848003.242926.png 1341848003.243104 depth/1341848003.243104.png
1341848003.278886 rgb/1341848003.278886.png 1341848003.278901 depth/1341848003.278901.png
1341848003.310739 rgb/1341848003.310739.png 1341848003.310752 depth/1341848003.310752.png
1341848003.342708 rgb/1341848003.342708.png 1341848003.342720 depth/1341848003.342720.png
1341848003.378999 rgb/1341848003.378999.png 1341848003.379019 depth/1341848003.379019.png
1341848003.410779 rgb/1341848003.410779.png 1341848003.410799 depth/1341848003.410799.png
1341848003.442728 rgb/1341848003.442728.png 1341848003.442757 depth/1341848003.442757.png
1341848003.478703 rgb/1341848003.478703.png 1341848003.478734 depth/1341848003.478734.png
1341848003.510700 rgb/1341848003.510700.png 1341848003.510745 depth/1341848003.510745.png
1341848003.546854 rgb/1341848003.546854.png 1341848003.548421 depth/1341848003.548421.png
1341848003.578749 rgb/1341848003.578749.png 1341848003.578762 depth/1341848003.578762.png
1341848003.617886 rgb/1341848003.617886.png 1341848003.617927 depth/1341848003.617927.png
1341848003.649972 rgb/1341848003.649972.png 1341848003.649997 depth/1341848003.649997.png
1341848003.685816 rgb/1341848003.685816.png 1341848003.685833 depth/1341848003.685833.png
1341848003.717853 rgb/1341848003.717853.png 1341848003.718179 depth/1341848003.718179.png
1341848003.753761 rgb/1341848003.753761.png 1341848003.753810 depth/1341848003.753810.png
1341848003.785807 rgb/1341848003.785807.png 1341848003.785825 depth/1341848003.785825.png
1341848003.817941 rgb/1341848003.817941.png 1341848003.817959 depth/1341848003.817959.png
1341848003.853971 rgb/1341848003.853971.png 1341848003.853983 depth/1341848003.853983.png
1341848003.885751 rgb/1341848003.885751.png 1341848003.885767 depth/1341848003.885767.png
1341848003.921688 rgb/1341848003.921688.png 1341848003.921702 depth/1341848003.921702.png
1341848003.953824 rgb/1341848003.953824.png 1341848003.953837 depth/1341848003.953837.png
1341848003.985789 rgb/1341848003.985789.png 1341848003.986490 depth/1341848003.986490.png
1341848004.021643 rgb/1341848004.021643.png 1341848004.021656 depth/1341848004.021656.png
1341848004.053778 rgb/1341848004.053778.png 1341848004.053793 depth/1341848004.053793.png
1341848004.089723 rgb/1341848004.089723.png 1341848004.089739 depth/1341848004.089739.png
1341848004.121698 rgb/1341848004.121698.png 1341848004.121723 depth/1341848004.121723.png
1341848004.153695 rgb/1341848004.153695.png 1341848004.154409 depth/1341848004.154409.png
1341848004.189785 rgb/1341848004.189785.png 1341848004.189798 depth/1341848004.189798.png
1341848004.221773 rgb/1341848004.221773.png 1341848004.221783 depth/1341848004.221783.png
1341848004.257760 rgb/1341848004.257760.png 1341848004.257772 depth/1341848004.257772.png
1341848004.289843 rgb/1341848004.289843.png 1341848004.289860 depth/1341848004.289860.png
1341848004.321820 rgb/1341848004.321820.png 1341848004.321834 depth/1341848004.321834.png
1341848004.357934 rgb/1341848004.357934.png 1341848004.357948 depth/1341848004.357948.png
1341848004.389781 rgb/1341848004.389781.png 1341848004.389798 depth/1341848004.389798.png
1341848004.421857 rgb/1341848004.421857.png 1341848004.421982 depth/1341848004.421982.png
1341848004.457752 rgb/1341848004.457752.png 1341848004.457769 depth/1341848004.457769.png
1341848004.489793 rgb/1341848004.489793.png 1341848004.489811 depth/1341848004.489811.png
1341848004.525726 rgb/1341848004.525726.png 1341848004.525737 depth/1341848004.525737.png
1341848004.557784 rgb/1341848004.557784.png 1341848004.557799 depth/1341848004.557799.png
1341848004.589761 rgb/1341848004.589761.png 1341848004.590427 depth/1341848004.590427.png
1341848004.625757 rgb/1341848004.625757.png 1341848004.625778 depth/1341848004.625778.png
1341848004.657882 rgb/1341848004.657882.png 1341848004.657913 depth/1341848004.657913.png
1341848004.689871 rgb/1341848004.689871.png 1341848004.689888 depth/1341848004.689888.png
1341848004.725815 rgb/1341848004.725815.png 1341848004.725831 depth/1341848004.725831.png
1341848004.757723 rgb/1341848004.757723.png 1341848004.757745 depth/1341848004.757745.png
1341848004.789709 rgb/1341848004.789709.png 1341848004.789719 depth/1341848004.789719.png
1341848004.825782 rgb/1341848004.825782.png 1341848004.825792 depth/1341848004.825792.png
1341848004.857706 rgb/1341848004.857706.png 1341848004.857726 depth/1341848004.857726.png
1341848004.889791 rgb/1341848004.889791.png 1341848004.889806 depth/1341848004.889806.png
1341848004.925788 rgb/1341848004.925788.png 1341848004.925821 depth/1341848004.925821.png
1341848004.957758 rgb/1341848004.957758.png 1341848004.957773 depth/1341848004.957773.png
1341848004.993849 rgb/1341848004.993849.png 1341848004.993863 depth/1341848004.993863.png
1341848005.025661 rgb/1341848005.025661.png 1341848005.025661 depth/1341848005.025661.png
1341848005.057739 rgb/1341848005.057739.png 1341848005.058466 depth/1341848005.058466.png
1341848005.093879 rgb/1341848005.093879.png 1341848005.093906 depth/1341848005.093906.png
1341848005.125700 rgb/1341848005.125700.png 1341848005.125710 depth/1341848005.125710.png
1341848005.157668 rgb/1341848005.157668.png 1341848005.157676 depth/1341848005.157676.png
1341848005.193749 rgb/1341848005.193749.png 1341848005.193763 depth/1341848005.193763.png
1341848005.225713 rgb/1341848005.225713.png 1341848005.225725 depth/1341848005.225725.png
1341848005.257748 rgb/1341848005.257748.png 1341848005.257761 depth/1341848005.257761.png
1341848005.293718 rgb/1341848005.293718.png 1341848005.293733 depth/1341848005.293733.png
1341848005.325870 rgb/1341848005.325870.png 1341848005.325901 depth/1341848005.325901.png
1341848005.357655 rgb/1341848005.357655.png 1341848005.357695 depth/1341848005.357695.png
1341848005.393694 rgb/1341848005.393694.png 1341848005.393707 depth/1341848005.393707.png
1341848005.425692 rgb/1341848005.425692.png 1341848005.425710 depth/1341848005.425710.png
1341848005.461850 rgb/1341848005.461850.png 1341848005.461862 depth/1341848005.461862.png
1341848005.493689 rgb/1341848005.493689.png 1341848005.493702 depth/1341848005.493702.png
1341848005.525844 rgb/1341848005.525844.png 1341848005.526425 depth/1341848005.526425.png
1341848005.561789 rgb/1341848005.561789.png 1341848005.561806 depth/1341848005.561806.png
1341848005.593673 rgb/1341848005.593673.png 1341848005.593689 depth/1341848005.593689.png
1341848005.629831 rgb/1341848005.629831.png 1341848005.629854 depth/1341848005.629854.png
1341848005.661802 rgb/1341848005.661802.png 1341848005.661818 depth/1341848005.661818.png
1341848005.693760 rgb/1341848005.693760.png 1341848005.693782 depth/1341848005.693782.png
1341848005.729741 rgb/1341848005.729741.png 1341848005.729756 depth/1341848005.729756.png
1341848005.761746 rgb/1341848005.761746.png 1341848005.761763 depth/1341848005.761763.png
1341848005.797852 rgb/1341848005.797852.png 1341848005.797870 depth/1341848005.797870.png
1341848005.829917 rgb/1341848005.829917.png 1341848005.829931 depth/1341848005.829931.png
1341848005.861699 rgb/1341848005.861699.png 1341848005.861711 depth/1341848005.861711.png
1341848005.897793 rgb/1341848005.897793.png 1341848005.897803 depth/1341848005.897803.png
1341848005.929656 rgb/1341848005.929656.png 1341848005.929669 depth/1341848005.929669.png
1341848005.965681 rgb/1341848005.965681.png 1341848005.965690 depth/1341848005.965690.png
1341848005.997804 rgb/1341848005.997804.png 1341848005.997817 depth/1341848005.997817.png
1341848006.029768 rgb/1341848006.029768.png 1341848006.029788 depth/1341848006.029788.png
1341848006.065849 rgb/1341848006.065849.png 1341848006.065861 depth/1341848006.065861.png
1341848006.097854 rgb/1341848006.097854.png 1341848006.097878 depth/1341848006.097878.png
1341848006.133683 rgb/1341848006.133683.png 1341848006.133702 depth/1341848006.133702.png
1341848006.165815 rgb/1341848006.165815.png 1341848006.165828 depth/1341848006.165828.png
1341848006.197589 rgb/1341848006.197589.png 1341848006.197630 depth/1341848006.197630.png
1341848006.233778 rgb/1341848006.233778.png 1341848006.233815 depth/1341848006.233815.png
1341848006.265787 rgb/1341848006.265787.png 1341848006.265800 depth/1341848006.265800.png
1341848006.301762 rgb/1341848006.301762.png 1341848006.301785 depth/1341848006.301785.png
1341848006.333717 rgb/1341848006.333717.png 1341848006.333730 depth/1341848006.333730.png
1341848006.366035 rgb/1341848006.366035.png 1341848006.366634 depth/1341848006.366634.png
1341848006.401760 rgb/1341848006.401760.png 1341848006.401777 depth/1341848006.401777.png
1341848006.433710 rgb/1341848006.433710.png 1341848006.433743 depth/1341848006.433743.png
1341848006.469715 rgb/1341848006.469715.png 1341848006.469729 depth/1341848006.469729.png
1341848006.501659 rgb/1341848006.501659.png 1341848006.501683 depth/1341848006.501683.png
1341848006.533741 rgb/1341848006.533741.png 1341848006.533763 depth/1341848006.533763.png
1341848006.569740 rgb/1341848006.569740.png 1341848006.569755 depth/1341848006.569755.png
1341848006.601774 rgb/1341848006.601774.png 1341848006.602403 depth/1341848006.602403.png
1341848006.637780 rgb/1341848006.637780.png 1341848006.637885 depth/1341848006.637885.png
1341848006.670119 rgb/1341848006.670119.png 1341848006.670137 depth/1341848006.670137.png
1341848006.701798 rgb/1341848006.701798.png 1341848006.701816 depth/1341848006.701816.png
1341848006.737817 rgb/1341848006.737817.png 1341848006.737832 depth/1341848006.737832.png
1341848006.769742 rgb/1341848006.769742.png 1341848006.769771 depth/1341848006.769771.png
1341848006.801940 rgb/1341848006.801940.png 1341848006.801992 depth/1341848006.801992.png
1341848006.837619 rgb/1341848006.837619.png 1341848006.837904 depth/1341848006.837904.png
1341848006.870724 rgb/1341848006.870724.png 1341848006.870742 depth/1341848006.870742.png
1341848006.901756 rgb/1341848006.901756.png 1341848006.901778 depth/1341848006.901778.png
1341848006.937738 rgb/1341848006.937738.png 1341848006.937752 depth/1341848006.937752.png
1341848006.969708 rgb/1341848006.969708.png 1341848006.969722 depth/1341848006.969722.png
1341848007.005802 rgb/1341848007.005802.png 1341848007.005815 depth/1341848007.005815.png
1341848007.037835 rgb/1341848007.037835.png 1341848007.037850 depth/1341848007.037850.png
1341848007.069678 rgb/1341848007.069678.png 1341848007.069726 depth/1341848007.069726.png
1341848007.105687 rgb/1341848007.105687.png 1341848007.105713 depth/1341848007.105713.png
1341848007.137866 rgb/1341848007.137866.png 1341848007.138464 depth/1341848007.138464.png
1341848007.169651 rgb/1341848007.169651.png 1341848007.169667 depth/1341848007.169667.png
1341848007.205747 rgb/1341848007.205747.png 1341848007.205760 depth/1341848007.205760.png
1341848007.237921 rgb/1341848007.237921.png 1341848007.237958 depth/1341848007.237958.png
1341848007.298875 rgb/1341848007.298875.png 1341848007.298924 depth/1341848007.298924.png
1341848007.331423 rgb/1341848007.331423.png 1341848007.331488 depth/1341848007.331488.png
1341848007.366699 rgb/1341848007.366699.png 1341848007.366720 depth/1341848007.366720.png
1341848007.398700 rgb/1341848007.398700.png 1341848007.398712 depth/1341848007.398712.png
1341848007.434791 rgb/1341848007.434791.png 1341848007.434822 depth/1341848007.434822.png
1341848007.466689 rgb/1341848007.466689.png 1341848007.466740 depth/1341848007.466740.png
1341848007.498756 rgb/1341848007.498756.png 1341848007.498777 depth/1341848007.498777.png
1341848007.534834 rgb/1341848007.534834.png 1341848007.534850 depth/1341848007.534850.png
1341848007.566719 rgb/1341848007.566719.png 1341848007.566737 depth/1341848007.566737.png
1341848007.598725 rgb/1341848007.598725.png 1341848007.598741 depth/1341848007.598741.png
1341848007.634799 rgb/1341848007.634799.png 1341848007.634838 depth/1341848007.634838.png
1341848007.666675 rgb/1341848007.666675.png 1341848007.666683 depth/1341848007.666683.png
1341848007.702797 rgb/1341848007.702797.png 1341848007.702831 depth/1341848007.702831.png
1341848007.734605 rgb/1341848007.734605.png 1341848007.734671 depth/1341848007.734671.png
1341848007.766913 rgb/1341848007.766913.png 1341848007.766939 depth/1341848007.766939.png
1341848007.802889 rgb/1341848007.802889.png 1341848007.802912 depth/1341848007.802912.png
1341848007.834962 rgb/1341848007.834962.png 1341848007.834998 depth/1341848007.834998.png
1341848007.866745 rgb/1341848007.866745.png 1341848007.866768 depth/1341848007.866768.png
1341848007.902779 rgb/1341848007.902779.png 1341848007.902804 depth/1341848007.902804.png
1341848007.934851 rgb/1341848007.934851.png 1341848007.934873 depth/1341848007.934873.png
1341848007.970690 rgb/1341848007.970690.png 1341848007.970706 depth/1341848007.970706.png
1341848008.002709 rgb/1341848008.002709.png 1341848008.002724 depth/1341848008.002724.png
1341848008.034820 rgb/1341848008.034820.png 1341848008.034876 depth/1341848008.034876.png
1341848008.070825 rgb/1341848008.070825.png 1341848008.070834 depth/1341848008.070834.png
1341848008.103209 rgb/1341848008.103209.png 1341848008.103236 depth/1341848008.103236.png
1341848008.138809 rgb/1341848008.138809.png 1341848008.138821 depth/1341848008.138821.png
1341848008.171058 rgb/1341848008.171058.png 1341848008.171117 depth/1341848008.171117.png
1341848008.202734 rgb/1341848008.202734.png 1341848008.202763 depth/1341848008.202763.png
1341848008.238657 rgb/1341848008.238657.png 1341848008.238773 depth/1341848008.238773.png
1341848008.270710 rgb/1341848008.270710.png 1341848008.270729 depth/1341848008.270729.png
1341848008.302748 rgb/1341848008.302748.png 1341848008.302791 depth/1341848008.302791.png
1341848008.338769 rgb/1341848008.338769.png 1341848008.338801 depth/1341848008.338801.png
1341848008.370731 rgb/1341848008.370731.png 1341848008.370758 depth/1341848008.370758.png
1341848008.438870 rgb/1341848008.438870.png 1341848008.438900 depth/1341848008.438900.png
1341848008.470807 rgb/1341848008.470807.png 1341848008.471606 depth/1341848008.471606.png
1341848008.506855 rgb/1341848008.506855.png 1341848008.506888 depth/1341848008.506888.png
1341848008.538786 rgb/1341848008.538786.png 1341848008.538800 depth/1341848008.538800.png
1341848008.570727 rgb/1341848008.570727.png 1341848008.571285 depth/1341848008.571285.png
1341848008.606698 rgb/1341848008.606698.png 1341848008.606724 depth/1341848008.606724.png
1341848008.638714 rgb/1341848008.638714.png 1341848008.638729 depth/1341848008.638729.png
1341848008.674639 rgb/1341848008.674639.png 1341848008.674663 depth/1341848008.674663.png
1341848008.706785 rgb/1341848008.706785.png 1341848008.706846 depth/1341848008.706846.png
1341848008.738678 rgb/1341848008.738678.png 1341848008.738715 depth/1341848008.738715.png
1341848008.775071 rgb/1341848008.775071.png 1341848008.775111 depth/1341848008.775111.png
1341848008.806865 rgb/1341848008.806865.png 1341848008.806917 depth/1341848008.806917.png
1341848008.838798 rgb/1341848008.838798.png 1341848008.838814 depth/1341848008.838814.png
1341848008.874631 rgb/1341848008.874631.png 1341848008.875086 depth/1341848008.875086.png
1341848008.906680 rgb/1341848008.906680.png 1341848008.906700 depth/1341848008.906700.png
1341848008.943051 rgb/1341848008.943051.png 1341848008.943141 depth/1341848008.943141.png
1341848008.974723 rgb/1341848008.974723.png 1341848008.974742 depth/1341848008.974742.png
1341848009.006825 rgb/1341848009.006825.png 1341848009.006865 depth/1341848009.006865.png
1341848009.042740 rgb/1341848009.042740.png 1341848009.042907 depth/1341848009.042907.png
1341848009.110807 rgb/1341848009.110807.png 1341848009.110847 depth/1341848009.110847.png
1341848009.142732 rgb/1341848009.142732.png 1341848009.142810 depth/1341848009.142810.png
1341848009.174693 rgb/1341848009.174693.png 1341848009.174705 depth/1341848009.174705.png
1341848009.210697 rgb/1341848009.210697.png 1341848009.210730 depth/1341848009.210730.png
1341848009.242869 rgb/1341848009.242869.png 1341848009.243384 depth/1341848009.243384.png
1341848009.274683 rgb/1341848009.274683.png 1341848009.274703 depth/1341848009.274703.png
1341848009.310898 rgb/1341848009.310898.png 1341848009.310929 depth/1341848009.310929.png
1341848009.342882 rgb/1341848009.342882.png 1341848009.342912 depth/1341848009.342912.png
1341848009.378700 rgb/1341848009.378700.png 1341848009.378717 depth/1341848009.378717.png
1341848009.442927 rgb/1341848009.442927.png 1341848009.443003 depth/1341848009.443003.png
1341848009.479022 rgb/1341848009.479022.png 1341848009.479061 depth/1341848009.479061.png
1341848009.510631 rgb/1341848009.510631.png 1341848009.510651 depth/1341848009.510651.png
1341848009.542815 rgb/1341848009.542815.png 1341848009.542831 depth/1341848009.542831.png
1341848009.578814 rgb/1341848009.578814.png 1341848009.578828 depth/1341848009.578828.png
1341848009.610955 rgb/1341848009.610955.png 1341848009.610985 depth/1341848009.610985.png
1341848009.646873 rgb/1341848009.646873.png 1341848009.646890 depth/1341848009.646890.png
1341848009.678666 rgb/1341848009.678666.png 1341848009.678709 depth/1341848009.678709.png
1341848009.710835 rgb/1341848009.710835.png 1341848009.710857 depth/1341848009.710857.png
1341848009.746819 rgb/1341848009.746819.png 1341848009.746840 depth/1341848009.746840.png
1341848009.778767 rgb/1341848009.778767.png 1341848009.778966 depth/1341848009.778966.png
1341848009.810661 rgb/1341848009.810661.png 1341848009.810678 depth/1341848009.810678.png
1341848009.846800 rgb/1341848009.846800.png 1341848009.846812 depth/1341848009.846812.png
1341848009.878688 rgb/1341848009.878688.png 1341848009.878704 depth/1341848009.878704.png
1341848009.914782 rgb/1341848009.914782.png 1341848009.914830 depth/1341848009.914830.png
1341848009.946990 rgb/1341848009.946990.png 1341848009.947019 depth/1341848009.947019.png
1341848009.978905 rgb/1341848009.978905.png 1341848009.979030 depth/1341848009.979030.png
1341848010.014819 rgb/1341848010.014819.png 1341848010.014838 depth/1341848010.014838.png
1341848010.046835 rgb/1341848010.046835.png 1341848010.047807 depth/1341848010.047807.png
1341848010.082650 rgb/1341848010.082650.png 1341848010.082721 depth/1341848010.082721.png
1341848010.114748 rgb/1341848010.114748.png 1341848010.114802 depth/1341848010.114802.png
1341848010.146752 rgb/1341848010.146752.png 1341848010.146785 depth/1341848010.146785.png
1341848010.182709 rgb/1341848010.182709.png 1341848010.182775 depth/1341848010.182775.png
1341848010.214739 rgb/1341848010.214739.png 1341848010.214759 depth/1341848010.214759.png
1341848010.246831 rgb/1341848010.246831.png 1341848010.246841 depth/1341848010.246841.png
1341848010.282749 rgb/1341848010.282749.png 1341848010.282781 depth/1341848010.282781.png
1341848010.314754 rgb/1341848010.314754.png 1341848010.314763 depth/1341848010.314763.png
1341848010.351054 rgb/1341848010.351054.png 1341848010.351621 depth/1341848010.351621.png
1341848010.382819 rgb/1341848010.382819.png 1341848010.382839 depth/1341848010.382839.png
1341848010.414692 rgb/1341848010.414692.png 1341848010.414716 depth/1341848010.414716.png
1341848010.450872 rgb/1341848010.450872.png 1341848010.450889 depth/1341848010.450889.png
1341848010.483088 rgb/1341848010.483088.png 1341848010.483600 depth/1341848010.483600.png
1341848010.514760 rgb/1341848010.514760.png 1341848010.514800 depth/1341848010.514800.png
1341848010.550631 rgb/1341848010.550631.png 1341848010.550812 depth/1341848010.550812.png
1341848010.582861 rgb/1341848010.582861.png 1341848010.582885 depth/1341848010.582885.png
1341848010.618690 rgb/1341848010.618690.png 1341848010.618730 depth/1341848010.618730.png
1341848010.650956 rgb/1341848010.650956.png 1341848010.650976 depth/1341848010.650976.png
1341848010.682633 rgb/1341848010.682633.png 1341848010.682652 depth/1341848010.682652.png
1341848010.718753 rgb/1341848010.718753.png 1341848010.719184 depth/1341848010.719184.png
1341848010.750922 rgb/1341848010.750922.png 1341848010.751486 depth/1341848010.751486.png
1341848010.782711 rgb/1341848010.782711.png 1341848010.782730 depth/1341848010.782730.png
1341848010.818844 rgb/1341848010.818844.png 1341848010.818854 depth/1341848010.818854.png
1341848010.850765 rgb/1341848010.850765.png 1341848010.851350 depth/1341848010.851350.png
1341848010.886687 rgb/1341848010.886687.png 1341848010.886724 depth/1341848010.886724.png
1341848010.918833 rgb/1341848010.918833.png 1341848010.918846 depth/1341848010.918846.png
1341848010.950793 rgb/1341848010.950793.png 1341848010.951377 depth/1341848010.951377.png
1341848010.986761 rgb/1341848010.986761.png 1341848010.986772 depth/1341848010.986772.png
1341848011.018704 rgb/1341848011.018704.png 1341848011.019273 depth/1341848011.019273.png
1341848011.051016 rgb/1341848011.051016.png 1341848011.051039 depth/1341848011.051039.png
1341848011.086749 rgb/1341848011.086749.png 1341848011.086773 depth/1341848011.086773.png
1341848011.118701 rgb/1341848011.118701.png 1341848011.118723 depth/1341848011.118723.png
1341848011.154630 rgb/1341848011.154630.png 1341848011.154649 depth/1341848011.154649.png
1341848011.186671 rgb/1341848011.186671.png 1341848011.186703 depth/1341848011.186703.png
1341848011.219095 rgb/1341848011.219095.png 1341848011.219111 depth/1341848011.219111.png
1341848011.254693 rgb/1341848011.254693.png 1341848011.254713 depth/1341848011.254713.png
1341848011.286627 rgb/1341848011.286627.png 1341848011.286673 depth/1341848011.286673.png
1341848011.322712 rgb/1341848011.322712.png 1341848011.322826 depth/1341848011.322826.png
1341848011.354750 rgb/1341848011.354750.png 1341848011.354764 depth/1341848011.354764.png
1341848011.386749 rgb/1341848011.386749.png 1341848011.386775 depth/1341848011.386775.png
1341848011.422722 rgb/1341848011.422722.png 1341848011.422732 depth/1341848011.422732.png
1341848011.454654 rgb/1341848011.454654.png 1341848011.454701 depth/1341848011.454701.png
1341848011.486754 rgb/1341848011.486754.png 1341848011.486777 depth/1341848011.486777.png
1341848011.522854 rgb/1341848011.522854.png 1341848011.522895 depth/1341848011.522895.png
1341848011.554674 rgb/1341848011.554674.png 1341848011.554735 depth/1341848011.554735.png
1341848011.590867 rgb/1341848011.590867.png 1341848011.590936 depth/1341848011.590936.png
1341848011.622723 rgb/1341848011.622723.png 1341848011.622767 depth/1341848011.622767.png
1341848011.654892 rgb/1341848011.654892.png 1341848011.655386 depth/1341848011.655386.png
1341848011.690778 rgb/1341848011.690778.png 1341848011.690790 depth/1341848011.690790.png
1341848011.722610 rgb/1341848011.722610.png 1341848011.722645 depth/1341848011.722645.png
1341848011.754796 rgb/1341848011.754796.png 1341848011.754833 depth/1341848011.754833.png
1341848011.790831 rgb/1341848011.790831.png 1341848011.790843 depth/1341848011.790843.png
1341848011.822705 rgb/1341848011.822705.png 1341848011.822722 depth/1341848011.822722.png
1341848011.858763 rgb/1341848011.858763.png 1341848011.859228 depth/1341848011.859228.png
1341848011.890689 rgb/1341848011.890689.png 1341848011.890702 depth/1341848011.890702.png
1341848011.922914 rgb/1341848011.922914.png 1341848011.923583 depth/1341848011.923583.png
1341848011.958828 rgb/1341848011.958828.png 1341848011.958858 depth/1341848011.958858.png
1341848011.990755 rgb/1341848011.990755.png 1341848011.991385 depth/1341848011.991385.png
1341848012.022737 rgb/1341848012.022737.png 1341848012.022777 depth/1341848012.022777.png
1341848012.058861 rgb/1341848012.058861.png 1341848012.058886 depth/1341848012.058886.png
1341848012.090822 rgb/1341848012.090822.png 1341848012.091474 depth/1341848012.091474.png
1341848012.126859 rgb/1341848012.126859.png 1341848012.126875 depth/1341848012.126875.png
1341848012.190967 rgb/1341848012.190967.png 1341848012.191005 depth/1341848012.191005.png
1341848012.226750 rgb/1341848012.226750.png 1341848012.226789 depth/1341848012.226789.png
1341848012.258713 rgb/1341848012.258713.png 1341848012.258767 depth/1341848012.258767.png
1341848012.295247 rgb/1341848012.295247.png 1341848012.295262 depth/1341848012.295262.png
1341848012.326868 rgb/1341848012.326868.png 1341848012.326913 depth/1341848012.326913.png
1341848012.358782 rgb/1341848012.358782.png 1341848012.359263 depth/1341848012.359263.png
1341848012.394721 rgb/1341848012.394721.png 1341848012.394744 depth/1341848012.394744.png
1341848012.426830 rgb/1341848012.426830.png 1341848012.426870 depth/1341848012.426870.png
1341848012.458805 rgb/1341848012.458805.png 1341848012.458819 depth/1341848012.458819.png
1341848012.494697 rgb/1341848012.494697.png 1341848012.494718 depth/1341848012.494718.png
1341848012.526756 rgb/1341848012.526756.png 1341848012.526771 depth/1341848012.526771.png
1341848012.562690 rgb/1341848012.562690.png 1341848012.562751 depth/1341848012.562751.png
1341848012.594669 rgb/1341848012.594669.png 1341848012.595251 depth/1341848012.595251.png
1341848012.626774 rgb/1341848012.626774.png 1341848012.626789 depth/1341848012.626789.png
1341848012.662763 rgb/1341848012.662763.png 1341848012.662786 depth/1341848012.662786.png
1341848012.695339 rgb/1341848012.695339.png 1341848012.695354 depth/1341848012.695354.png
1341848012.726854 rgb/1341848012.726854.png 1341848012.726885 depth/1341848012.726885.png
1341848012.762672 rgb/1341848012.762672.png 1341848012.762686 depth/1341848012.762686.png
1341848012.794727 rgb/1341848012.794727.png 1341848012.794773 depth/1341848012.794773.png
1341848012.830669 rgb/1341848012.830669.png 1341848012.830698 depth/1341848012.830698.png
1341848012.862795 rgb/1341848012.862795.png 1341848012.862809 depth/1341848012.862809.png
1341848012.894740 rgb/1341848012.894740.png 1341848012.894767 depth/1341848012.894767.png
1341848012.930848 rgb/1341848012.930848.png 1341848012.930882 depth/1341848012.930882.png
1341848012.962752 rgb/1341848012.962752.png 1341848012.962985 depth/1341848012.962985.png
1341848012.994842 rgb/1341848012.994842.png 1341848012.994868 depth/1341848012.994868.png
1341848013.030944 rgb/1341848013.030944.png 1341848013.030973 depth/1341848013.030973.png
1341848013.062714 rgb/1341848013.062714.png 1341848013.063076 depth/1341848013.063076.png
1341848013.098784 rgb/1341848013.098784.png 1341848013.098799 depth/1341848013.098799.png
1341848013.130817 rgb/1341848013.130817.png 1341848013.130848 depth/1341848013.130848.png
1341848013.162759 rgb/1341848013.162759.png 1341848013.162778 depth/1341848013.162778.png
1341848013.198719 rgb/1341848013.198719.png 1341848013.198734 depth/1341848013.198734.png
1341848013.230855 rgb/1341848013.230855.png 1341848013.230869 depth/1341848013.230869.png
1341848013.262723 rgb/1341848013.262723.png 1341848013.262743 depth/1341848013.262743.png
1341848013.298709 rgb/1341848013.298709.png 1341848013.298774 depth/1341848013.298774.png
1341848013.330754 rgb/1341848013.330754.png 1341848013.330792 depth/1341848013.330792.png
1341848013.366705 rgb/1341848013.366705.png 1341848013.366741 depth/1341848013.366741.png
1341848013.398748 rgb/1341848013.398748.png 1341848013.398774 depth/1341848013.398774.png
1341848013.430850 rgb/1341848013.430850.png 1341848013.430871 depth/1341848013.430871.png
1341848013.466959 rgb/1341848013.466959.png 1341848013.466977 depth/1341848013.466977.png
1341848013.498782 rgb/1341848013.498782.png 1341848013.498821 depth/1341848013.498821.png
1341848013.534779 rgb/1341848013.534779.png 1341848013.534803 depth/1341848013.534803.png
1341848013.566664 rgb/1341848013.566664.png 1341848013.566708 depth/1341848013.566708.png
1341848013.598764 rgb/1341848013.598764.png 1341848013.598783 depth/1341848013.598783.png
1341848013.634812 rgb/1341848013.634812.png 1341848013.634835 depth/1341848013.634835.png
1341848013.666669 rgb/1341848013.666669.png 1341848013.666681 depth/1341848013.666681.png
1341848013.698821 rgb/1341848013.698821.png 1341848013.698836 depth/1341848013.698836.png
1341848013.734623 rgb/1341848013.734623.png 1341848013.734633 depth/1341848013.734633.png
1341848013.766827 rgb/1341848013.766827.png 1341848013.766854 depth/1341848013.766854.png
1341848013.802717 rgb/1341848013.802717.png 1341848013.802736 depth/1341848013.802736.png
1341848013.834802 rgb/1341848013.834802.png 1341848013.834816 depth/1341848013.834816.png
1341848013.866791 rgb/1341848013.866791.png 1341848013.866814 depth/1341848013.866814.png
1341848013.902735 rgb/1341848013.902735.png 1341848013.902763 depth/1341848013.902763.png
1341848013.966740 rgb/1341848013.966740.png 1341848013.966791 depth/1341848013.966791.png
1341848014.002717 rgb/1341848014.002717.png 1341848014.002734 depth/1341848014.002734.png
1341848014.034942 rgb/1341848014.034942.png 1341848014.034991 depth/1341848014.034991.png
1341848014.070990 rgb/1341848014.070990.png 1341848014.071022 depth/1341848014.071022.png
1341848014.102686 rgb/1341848014.102686.png 1341848014.102699 depth/1341848014.102699.png
1341848014.134725 rgb/1341848014.134725.png 1341848014.134744 depth/1341848014.134744.png
1341848014.170724 rgb/1341848014.170724.png 1341848014.170789 depth/1341848014.170789.png
1341848014.202658 rgb/1341848014.202658.png 1341848014.202677 depth/1341848014.202677.png
1341848014.234751 rgb/1341848014.234751.png 1341848014.234775 depth/1341848014.234775.png
1341848014.270714 rgb/1341848014.270714.png 1341848014.270773 depth/1341848014.270773.png
1341848014.302738 rgb/1341848014.302738.png 1341848014.302751 depth/1341848014.302751.png
1341848014.338694 rgb/1341848014.338694.png 1341848014.338717 depth/1341848014.338717.png
1341848014.370553 rgb/1341848014.370553.png 1341848014.370821 depth/1341848014.370821.png
1341848014.438848 rgb/1341848014.438848.png 1341848014.438869 depth/1341848014.438869.png
1341848014.470783 rgb/1341848014.470783.png 1341848014.470797 depth/1341848014.470797.png
1341848014.506633 rgb/1341848014.506633.png 1341848014.506658 depth/1341848014.506658.png
1341848014.538728 rgb/1341848014.538728.png 1341848014.538744 depth/1341848014.538744.png
1341848014.570790 rgb/1341848014.570790.png 1341848014.570803 depth/1341848014.570803.png
1341848014.606858 rgb/1341848014.606858.png 1341848014.606882 depth/1341848014.606882.png
1341848014.638688 rgb/1341848014.638688.png 1341848014.638705 depth/1341848014.638705.png
1341848014.670828 rgb/1341848014.670828.png 1341848014.671380 depth/1341848014.671380.png
1341848014.706765 rgb/1341848014.706765.png 1341848014.706993 depth/1341848014.706993.png
1341848014.738691 rgb/1341848014.738691.png 1341848014.738705 depth/1341848014.738705.png
1341848014.774750 rgb/1341848014.774750.png 1341848014.774767 depth/1341848014.774767.png
1341848014.806669 rgb/1341848014.806669.png 1341848014.806684 depth/1341848014.806684.png
1341848014.838740 rgb/1341848014.838740.png 1341848014.838775 depth/1341848014.838775.png
1341848014.874686 rgb/1341848014.874686.png 1341848014.874729 depth/1341848014.874729.png
1341848014.906647 rgb/1341848014.906647.png 1341848014.906657 depth/1341848014.906657.png
1341848014.938697 rgb/1341848014.938697.png 1341848014.938709 depth/1341848014.938709.png
1341848014.974705 rgb/1341848014.974705.png 1341848014.974719 depth/1341848014.974719.png
1341848015.006657 rgb/1341848015.006657.png 1341848015.006672 depth/1341848015.006672.png
1341848015.042593 rgb/1341848015.042593.png 1341848015.042656 depth/1341848015.042656.png
1341848015.074864 rgb/1341848015.074864.png 1341848015.074894 depth/1341848015.074894.png
1341848015.106838 rgb/1341848015.106838.png 1341848015.106864 depth/1341848015.106864.png
1341848015.142691 rgb/1341848015.142691.png 1341848015.142708 depth/1341848015.142708.png
1341848015.174708 rgb/1341848015.174708.png 1341848015.174741 depth/1341848015.174741.png
1341848015.207238 rgb/1341848015.207238.png 1341848015.207717 depth/1341848015.207717.png
1341848015.243495 rgb/1341848015.243495.png 1341848015.243592 depth/1341848015.243592.png
1341848015.274780 rgb/1341848015.274780.png 1341848015.274791 depth/1341848015.274791.png
1341848015.310598 rgb/1341848015.310598.png 1341848015.310805 depth/1341848015.310805.png
1341848015.342895 rgb/1341848015.342895.png 1341848015.342916 depth/1341848015.342916.png
1341848015.374733 rgb/1341848015.374733.png 1341848015.374754 depth/1341848015.374754.png
1341848015.410655 rgb/1341848015.410655.png 1341848015.410669 depth/1341848015.410669.png
1341848015.442783 rgb/1341848015.442783.png 1341848015.442801 depth/1341848015.442801.png
1341848015.474959 rgb/1341848015.474959.png 1341848015.474976 depth/1341848015.474976.png
1341848015.510927 rgb/1341848015.510927.png 1341848015.510957 depth/1341848015.510957.png
1341848015.542834 rgb/1341848015.542834.png 1341848015.543288 depth/1341848015.543288.png
1341848015.581753 rgb/1341848015.581753.png 1341848015.581781 depth/1341848015.581781.png
1341848015.617769 rgb/1341848015.617769.png 1341848015.618482 depth/1341848015.618482.png
1341848015.650094 rgb/1341848015.650094.png 1341848015.650136 depth/1341848015.650136.png
1341848015.685811 rgb/1341848015.685811.png 1341848015.685825 depth/1341848015.685825.png
1341848015.718057 rgb/1341848015.718057.png 1341848015.719587 depth/1341848015.719587.png
1341848015.749815 rgb/1341848015.749815.png 1341848015.749843 depth/1341848015.749843.png
1341848015.785761 rgb/1341848015.785761.png 1341848015.785775 depth/1341848015.785775.png
1341848015.817883 rgb/1341848015.817883.png 1341848015.817912 depth/1341848015.817912.png
1341848015.853811 rgb/1341848015.853811.png 1341848015.854043 depth/1341848015.854043.png
1341848015.885654 rgb/1341848015.885654.png 1341848015.885668 depth/1341848015.885668.png
1341848015.917793 rgb/1341848015.917793.png 1341848015.917819 depth/1341848015.917819.png
1341848015.954005 rgb/1341848015.954005.png 1341848015.954061 depth/1341848015.954061.png
1341848015.986663 rgb/1341848015.986663.png 1341848015.987003 depth/1341848015.987003.png
1341848016.021677 rgb/1341848016.021677.png 1341848016.021701 depth/1341848016.021701.png
1341848016.053936 rgb/1341848016.053936.png 1341848016.053969 depth/1341848016.053969.png
1341848016.085724 rgb/1341848016.085724.png 1341848016.085742 depth/1341848016.085742.png
1341848016.121844 rgb/1341848016.121844.png 1341848016.121873 depth/1341848016.121873.png
1341848016.153821 rgb/1341848016.153821.png 1341848016.153858 depth/1341848016.153858.png
1341848016.185769 rgb/1341848016.185769.png 1341848016.185803 depth/1341848016.185803.png
1341848016.221734 rgb/1341848016.221734.png 1341848016.221788 depth/1341848016.221788.png
1341848016.253686 rgb/1341848016.253686.png 1341848016.253706 depth/1341848016.253706.png
1341848016.289960 rgb/1341848016.289960.png 1341848016.289975 depth/1341848016.289975.png
1341848016.322013 rgb/1341848016.322013.png 1341848016.322971 depth/1341848016.322971.png
1341848016.353746 rgb/1341848016.353746.png 1341848016.354394 depth/1341848016.354394.png
1341848016.389789 rgb/1341848016.389789.png 1341848016.389816 depth/1341848016.389816.png
1341848016.421705 rgb/1341848016.421705.png 1341848016.422556 depth/1341848016.422556.png
1341848016.453901 rgb/1341848016.453901.png 1341848016.454511 depth/1341848016.454511.png
1341848016.490058 rgb/1341848016.490058.png 1341848016.490717 depth/1341848016.490717.png
1341848016.521813 rgb/1341848016.521813.png 1341848016.521830 depth/1341848016.521830.png
1341848016.554210 rgb/1341848016.554210.png 1341848016.554621 depth/1341848016.554621.png
1341848016.589825 rgb/1341848016.589825.png 1341848016.589841 depth/1341848016.589841.png
1341848016.621860 rgb/1341848016.621860.png 1341848016.622571 depth/1341848016.622571.png
1341848016.657837 rgb/1341848016.657837.png 1341848016.657879 depth/1341848016.657879.png
1341848016.689891 rgb/1341848016.689891.png 1341848016.689920 depth/1341848016.689920.png
1341848016.757848 rgb/1341848016.757848.png 1341848016.757902 depth/1341848016.757902.png
1341848016.818817 rgb/1341848016.818817.png 1341848016.818829 depth/1341848016.818829.png
1341848016.850754 rgb/1341848016.850754.png 1341848016.850779 depth/1341848016.850779.png
1341848016.882757 rgb/1341848016.882757.png 1341848016.882773 depth/1341848016.882773.png
1341848016.918907 rgb/1341848016.918907.png 1341848016.918954 depth/1341848016.918954.png
1341848016.950706 rgb/1341848016.950706.png 1341848016.950732 depth/1341848016.950732.png
1341848016.986658 rgb/1341848016.986658.png 1341848016.986668 depth/1341848016.986668.png
1341848017.018678 rgb/1341848017.018678.png 1341848017.018699 depth/1341848017.018699.png
1341848017.050760 rgb/1341848017.050760.png 1341848017.050790 depth/1341848017.050790.png
1341848017.086845 rgb/1341848017.086845.png 1341848017.087686 depth/1341848017.087686.png
1341848017.118641 rgb/1341848017.118641.png 1341848017.118659 depth/1341848017.118659.png
1341848017.150678 rgb/1341848017.150678.png 1341848017.150706 depth/1341848017.150706.png
1341848017.186855 rgb/1341848017.186855.png 1341848017.186867 depth/1341848017.186867.png
1341848017.218765 rgb/1341848017.218765.png 1341848017.218781 depth/1341848017.218781.png
1341848017.254693 rgb/1341848017.254693.png 1341848017.254710 depth/1341848017.254710.png
1341848017.286638 rgb/1341848017.286638.png 1341848017.286649 depth/1341848017.286649.png
1341848017.318695 rgb/1341848017.318695.png 1341848017.318710 depth/1341848017.318710.png
1341848017.354737 rgb/1341848017.354737.png 1341848017.354762 depth/1341848017.354762.png
1341848017.386825 rgb/1341848017.386825.png 1341848017.387567 depth/1341848017.387567.png
1341848017.418824 rgb/1341848017.418824.png 1341848017.418853 depth/1341848017.418853.png
1341848017.454792 rgb/1341848017.454792.png 1341848017.454807 depth/1341848017.454807.png
1341848017.486699 rgb/1341848017.486699.png 1341848017.486724 depth/1341848017.486724.png
1341848017.522694 rgb/1341848017.522694.png 1341848017.522742 depth/1341848017.522742.png
1341848017.554797 rgb/1341848017.554797.png 1341848017.554807 depth/1341848017.554807.png
1341848017.587838 rgb/1341848017.587838.png 1341848017.587857 depth/1341848017.587857.png
1341848017.622714 rgb/1341848017.622714.png 1341848017.622730 depth/1341848017.622730.png
1341848017.654814 rgb/1341848017.654814.png 1341848017.654844 depth/1341848017.654844.png
1341848017.686820 rgb/1341848017.686820.png 1341848017.686847 depth/1341848017.686847.png
1341848017.722837 rgb/1341848017.722837.png 1341848017.722849 depth/1341848017.722849.png
1341848017.754780 rgb/1341848017.754780.png 1341848017.754796 depth/1341848017.754796.png
1341848017.790699 rgb/1341848017.790699.png 1341848017.790714 depth/1341848017.790714.png
1341848017.822756 rgb/1341848017.822756.png 1341848017.823281 depth/1341848017.823281.png
1341848017.854726 rgb/1341848017.854726.png 1341848017.854745 depth/1341848017.854745.png
1341848017.890737 rgb/1341848017.890737.png 1341848017.890747 depth/1341848017.890747.png
1341848017.922823 rgb/1341848017.922823.png 1341848017.922849 depth/1341848017.922849.png
1341848017.958643 rgb/1341848017.958643.png 1341848017.958669 depth/1341848017.958669.png
1341848017.990683 rgb/1341848017.990683.png 1341848017.990698 depth/1341848017.990698.png
1341848018.022671 rgb/1341848018.022671.png 1341848018.022686 depth/1341848018.022686.png
1341848018.058766 rgb/1341848018.058766.png 1341848018.058780 depth/1341848018.058780.png
1341848018.090894 rgb/1341848018.090894.png 1341848018.091600 depth/1341848018.091600.png
1341848018.122747 rgb/1341848018.122747.png 1341848018.122774 depth/1341848018.122774.png
1341848018.159145 rgb/1341848018.159145.png 1341848018.159160 depth/1341848018.159160.png
1341848018.190824 rgb/1341848018.190824.png 1341848018.190833 depth/1341848018.190833.png
1341848018.226660 rgb/1341848018.226660.png 1341848018.226676 depth/1341848018.226676.png
1341848018.258766 rgb/1341848018.258766.png 1341848018.258776 depth/1341848018.258776.png
1341848018.290747 rgb/1341848018.290747.png 1341848018.290763 depth/1341848018.290763.png
1341848018.333905 rgb/1341848018.333905.png 1341848018.333920 depth/1341848018.333920.png
1341848018.367205 rgb/1341848018.367205.png 1341848018.367246 depth/1341848018.367246.png
1341848018.397728 rgb/1341848018.397728.png 1341848018.398249 depth/1341848018.398249.png
1341848018.433770 rgb/1341848018.433770.png 1341848018.433789 depth/1341848018.433789.png
1341848018.465663 rgb/1341848018.465663.png 1341848018.465797 depth/1341848018.465797.png
1341848018.501822 rgb/1341848018.501822.png 1341848018.501833 depth/1341848018.501833.png
1341848018.534507 rgb/1341848018.534507.png 1341848018.534528 depth/1341848018.534528.png
1341848018.565849 rgb/1341848018.565849.png 1341848018.565868 depth/1341848018.565868.png
1341848018.601739 rgb/1341848018.601739.png 1341848018.601762 depth/1341848018.601762.png
1341848018.633687 rgb/1341848018.633687.png 1341848018.633745 depth/1341848018.633745.png
1341848018.669811 rgb/1341848018.669811.png 1341848018.669908 depth/1341848018.669908.png
1341848018.701756 rgb/1341848018.701756.png 1341848018.701811 depth/1341848018.701811.png
1341848018.733853 rgb/1341848018.733853.png 1341848018.733907 depth/1341848018.733907.png
1341848018.769715 rgb/1341848018.769715.png 1341848018.769731 depth/1341848018.769731.png
1341848018.802234 rgb/1341848018.802234.png 1341848018.802331 depth/1341848018.802331.png
1341848018.833759 rgb/1341848018.833759.png 1341848018.833794 depth/1341848018.833794.png
1341848018.869787 rgb/1341848018.869787.png 1341848018.869812 depth/1341848018.869812.png
1341848018.901964 rgb/1341848018.901964.png 1341848018.902019 depth/1341848018.902019.png
1341848018.933795 rgb/1341848018.933795.png 1341848018.933805 depth/1341848018.933805.png
1341848018.969688 rgb/1341848018.969688.png 1341848018.969703 depth/1341848018.969703.png
1341848019.002336 rgb/1341848019.002336.png 1341848019.002352 depth/1341848019.002352.png
1341848019.069833 rgb/1341848019.069833.png 1341848019.069892 depth/1341848019.069892.png
1341848019.130792 rgb/1341848019.130792.png 1341848019.130828 depth/1341848019.130828.png
1341848019.162652 rgb/1341848019.162652.png 1341848019.162677 depth/1341848019.162677.png
1341848019.198644 rgb/1341848019.198644.png 1341848019.198662 depth/1341848019.198662.png
1341848019.231114 rgb/1341848019.231114.png 1341848019.231515 depth/1341848019.231515.png
1341848019.262728 rgb/1341848019.262728.png 1341848019.262747 depth/1341848019.262747.png
1341848019.298715 rgb/1341848019.298715.png 1341848019.298728 depth/1341848019.298728.png
1341848019.330680 rgb/1341848019.330680.png 1341848019.330801 depth/1341848019.330801.png
1341848019.362697 rgb/1341848019.362697.png 1341848019.362719 depth/1341848019.362719.png
1341848019.398715 rgb/1341848019.398715.png 1341848019.398731 depth/1341848019.398731.png
1341848019.431028 rgb/1341848019.431028.png 1341848019.431071 depth/1341848019.431071.png
1341848019.467021 rgb/1341848019.467021.png 1341848019.467528 depth/1341848019.467528.png
1341848019.498756 rgb/1341848019.498756.png 1341848019.498786 depth/1341848019.498786.png
1341848019.530821 rgb/1341848019.530821.png 1341848019.530845 depth/1341848019.530845.png
1341848019.567087 rgb/1341848019.567087.png 1341848019.567145 depth/1341848019.567145.png
1341848019.598737 rgb/1341848019.598737.png 1341848019.598763 depth/1341848019.598763.png
1341848019.630654 rgb/1341848019.630654.png 1341848019.630664 depth/1341848019.630664.png
1341848019.666875 rgb/1341848019.666875.png 1341848019.666895 depth/1341848019.666895.png
1341848019.698668 rgb/1341848019.698668.png 1341848019.698714 depth/1341848019.698714.png
1341848019.734756 rgb/1341848019.734756.png 1341848019.734778 depth/1341848019.734778.png
1341848019.766703 rgb/1341848019.766703.png 1341848019.767180 depth/1341848019.767180.png
1341848019.798719 rgb/1341848019.798719.png 1341848019.798730 depth/1341848019.798730.png
1341848019.834660 rgb/1341848019.834660.png 1341848019.835148 depth/1341848019.835148.png
1341848019.898833 rgb/1341848019.898833.png 1341848019.898856 depth/1341848019.898856.png
1341848019.934782 rgb/1341848019.934782.png 1341848019.935323 depth/1341848019.935323.png
1341848019.966705 rgb/1341848019.966705.png 1341848019.966718 depth/1341848019.966718.png
1341848020.002811 rgb/1341848020.002811.png 1341848020.002827 depth/1341848020.002827.png
1341848020.034693 rgb/1341848020.034693.png 1341848020.034751 depth/1341848020.034751.png
1341848020.066696 rgb/1341848020.066696.png 1341848020.066711 depth/1341848020.066711.png
1341848020.102776 rgb/1341848020.102776.png 1341848020.102828 depth/1341848020.102828.png
1341848020.134758 rgb/1341848020.134758.png 1341848020.134797 depth/1341848020.134797.png
1341848020.170835 rgb/1341848020.170835.png 1341848020.170870 depth/1341848020.170870.png
1341848020.202706 rgb/1341848020.202706.png 1341848020.202731 depth/1341848020.202731.png
1341848020.234873 rgb/1341848020.234873.png 1341848020.234962 depth/1341848020.234962.png
1341848020.271152 rgb/1341848020.271152.png 1341848020.271164 depth/1341848020.271164.png
1341848020.302754 rgb/1341848020.302754.png 1341848020.302781 depth/1341848020.302781.png
1341848020.334861 rgb/1341848020.334861.png 1341848020.334915 depth/1341848020.334915.png
1341848020.370812 rgb/1341848020.370812.png 1341848020.370828 depth/1341848020.370828.png
1341848020.438816 rgb/1341848020.438816.png 1341848020.438829 depth/1341848020.438829.png
1341848020.471200 rgb/1341848020.471200.png 1341848020.471215 depth/1341848020.471215.png
1341848020.502691 rgb/1341848020.502691.png 1341848020.502708 depth/1341848020.502708.png
1341848020.538748 rgb/1341848020.538748.png 1341848020.538775 depth/1341848020.538775.png
1341848020.570790 rgb/1341848020.570790.png 1341848020.570808 depth/1341848020.570808.png
1341848020.602764 rgb/1341848020.602764.png 1341848020.602784 depth/1341848020.602784.png
1341848020.638929 rgb/1341848020.638929.png 1341848020.638951 depth/1341848020.638951.png
1341848020.670809 rgb/1341848020.670809.png 1341848020.670825 depth/1341848020.670825.png
1341848020.706669 rgb/1341848020.706669.png 1341848020.706711 depth/1341848020.706711.png
1341848020.738994 rgb/1341848020.738994.png 1341848020.739029 depth/1341848020.739029.png
1341848020.770817 rgb/1341848020.770817.png 1341848020.770832 depth/1341848020.770832.png
1341848020.807216 rgb/1341848020.807216.png 1341848020.807293 depth/1341848020.807293.png
1341848020.839066 rgb/1341848020.839066.png 1341848020.839106 depth/1341848020.839106.png
1341848020.870955 rgb/1341848020.870955.png 1341848020.870982 depth/1341848020.870982.png
1341848020.906582 rgb/1341848020.906582.png 1341848020.906626 depth/1341848020.906626.png
1341848020.938790 rgb/1341848020.938790.png 1341848020.938813 depth/1341848020.938813.png
1341848020.974874 rgb/1341848020.974874.png 1341848020.974888 depth/1341848020.974888.png
1341848021.006632 rgb/1341848021.006632.png 1341848021.006653 depth/1341848021.006653.png
1341848021.039636 rgb/1341848021.039636.png 1341848021.039683 depth/1341848021.039683.png
1341848021.074762 rgb/1341848021.074762.png 1341848021.074778 depth/1341848021.074778.png
1341848021.106691 rgb/1341848021.106691.png 1341848021.106711 depth/1341848021.106711.png
1341848021.142795 rgb/1341848021.142795.png 1341848021.142912 depth/1341848021.142912.png
1341848021.175038 rgb/1341848021.175038.png 1341848021.175064 depth/1341848021.175064.png
1341848021.206698 rgb/1341848021.206698.png 1341848021.206716 depth/1341848021.206716.png
1341848021.242671 rgb/1341848021.242671.png 1341848021.242711 depth/1341848021.242711.png
1341848021.274899 rgb/1341848021.274899.png 1341848021.274910 depth/1341848021.274910.png
1341848021.307283 rgb/1341848021.307283.png 1341848021.307304 depth/1341848021.307304.png
1341848021.343359 rgb/1341848021.343359.png 1341848021.347770 depth/1341848021.347770.png
1341848021.384830 rgb/1341848021.384830.png 1341848021.385282 depth/1341848021.385282.png
1341848021.414272 rgb/1341848021.414272.png 1341848021.414623 depth/1341848021.414623.png
1341848021.455728 rgb/1341848021.455728.png 1341848021.456491 depth/1341848021.456491.png
1341848021.487906 rgb/1341848021.487906.png 1341848021.488948 depth/1341848021.488948.png
1341848021.514696 rgb/1341848021.514696.png 1341848021.514729 depth/1341848021.514729.png
1341848021.550755 rgb/1341848021.550755.png 1341848021.551117 depth/1341848021.551117.png
1341848021.617752 rgb/1341848021.617752.png 1341848021.618003 depth/1341848021.618003.png
1341848021.678764 rgb/1341848021.678764.png 1341848021.678782 depth/1341848021.678782.png
1341848021.710743 rgb/1341848021.710743.png 1341848021.710760 depth/1341848021.710760.png
1341848021.742811 rgb/1341848021.742811.png 1341848021.742825 depth/1341848021.742825.png
1341848021.778676 rgb/1341848021.778676.png 1341848021.779227 depth/1341848021.779227.png
1341848021.810867 rgb/1341848021.810867.png 1341848021.810903 depth/1341848021.810903.png
1341848021.844563 rgb/1341848021.844563.png 1341848021.844607 depth/1341848021.844607.png
1341848021.878887 rgb/1341848021.878887.png 1341848021.878906 depth/1341848021.878906.png
1341848021.910628 rgb/1341848021.910628.png 1341848021.910642 depth/1341848021.910642.png
1341848021.946714 rgb/1341848021.946714.png 1341848021.946736 depth/1341848021.946736.png
1341848021.978747 rgb/1341848021.978747.png 1341848021.978772 depth/1341848021.978772.png
1341848022.010782 rgb/1341848022.010782.png 1341848022.010803 depth/1341848022.010803.png
1341848022.046709 rgb/1341848022.046709.png 1341848022.046726 depth/1341848022.046726.png
1341848022.078665 rgb/1341848022.078665.png 1341848022.079245 depth/1341848022.079245.png
1341848022.110954 rgb/1341848022.110954.png 1341848022.111657 depth/1341848022.111657.png
1341848022.146749 rgb/1341848022.146749.png 1341848022.146788 depth/1341848022.146788.png
1341848022.178988 rgb/1341848022.178988.png 1341848022.179046 depth/1341848022.179046.png
1341848022.214773 rgb/1341848022.214773.png 1341848022.214790 depth/1341848022.214790.png
1341848022.246774 rgb/1341848022.246774.png 1341848022.247466 depth/1341848022.247466.png
1341848022.278764 rgb/1341848022.278764.png 1341848022.279313 depth/1341848022.279313.png
1341848022.314757 rgb/1341848022.314757.png 1341848022.314776 depth/1341848022.314776.png
1341848022.354110 rgb/1341848022.354110.png 1341848022.354136 depth/1341848022.354136.png
1341848022.387191 rgb/1341848022.387191.png 1341848022.388540 depth/1341848022.388540.png
1341848022.417848 rgb/1341848022.417848.png 1341848022.418465 depth/1341848022.418465.png
1341848022.454164 rgb/1341848022.454164.png 1341848022.454189 depth/1341848022.454189.png
1341848022.485638 rgb/1341848022.485638.png 1341848022.485655 depth/1341848022.485655.png
1341848022.521730 rgb/1341848022.521730.png 1341848022.522527 depth/1341848022.522527.png
1341848022.554231 rgb/1341848022.554231.png 1341848022.554515 depth/1341848022.554515.png
1341848022.586067 rgb/1341848022.586067.png 1341848022.586079 depth/1341848022.586079.png
1341848022.621801 rgb/1341848022.621801.png 1341848022.621834 depth/1341848022.621834.png
1341848022.654208 rgb/1341848022.654208.png 1341848022.654220 depth/1341848022.654220.png
1341848022.690287 rgb/1341848022.690287.png 1341848022.690339 depth/1341848022.690339.png
1341848022.721700 rgb/1341848022.721700.png 1341848022.722043 depth/1341848022.722043.png
1341848022.782985 rgb/1341848022.782985.png 1341848022.783028 depth/1341848022.783028.png
1341848022.814772 rgb/1341848022.814772.png 1341848022.814851 depth/1341848022.814851.png
1341848022.850799 rgb/1341848022.850799.png 1341848022.851481 depth/1341848022.851481.png
1341848022.882710 rgb/1341848022.882710.png 1341848022.882730 depth/1341848022.882730.png
1341848022.918835 rgb/1341848022.918835.png 1341848022.918869 depth/1341848022.918869.png
1341848022.950815 rgb/1341848022.950815.png 1341848022.950861 depth/1341848022.950861.png
1341848022.982728 rgb/1341848022.982728.png 1341848022.982744 depth/1341848022.982744.png
1341848023.018822 rgb/1341848023.018822.png 1341848023.018832 depth/1341848023.018832.png
1341848023.050766 rgb/1341848023.050766.png 1341848023.050781 depth/1341848023.050781.png
1341848023.082738 rgb/1341848023.082738.png 1341848023.082824 depth/1341848023.082824.png
1341848023.118789 rgb/1341848023.118789.png 1341848023.118804 depth/1341848023.118804.png
1341848023.150992 rgb/1341848023.150992.png 1341848023.151020 depth/1341848023.151020.png
1341848023.186687 rgb/1341848023.186687.png 1341848023.186714 depth/1341848023.186714.png
1341848023.218702 rgb/1341848023.218702.png 1341848023.218801 depth/1341848023.218801.png
1341848023.286758 rgb/1341848023.286758.png 1341848023.286974 depth/1341848023.286974.png
1341848023.318763 rgb/1341848023.318763.png 1341848023.318791 depth/1341848023.318791.png
1341848023.354762 rgb/1341848023.354762.png 1341848023.354851 depth/1341848023.354851.png
1341848023.386908 rgb/1341848023.386908.png 1341848023.387380 depth/1341848023.387380.png
1341848023.418717 rgb/1341848023.418717.png 1341848023.418747 depth/1341848023.418747.png
1341848023.454710 rgb/1341848023.454710.png 1341848023.454727 depth/1341848023.454727.png
1341848023.487092 rgb/1341848023.487092.png 1341848023.487102 depth/1341848023.487102.png
1341848023.518675 rgb/1341848023.518675.png 1341848023.518691 depth/1341848023.518691.png
1341848023.555068 rgb/1341848023.555068.png 1341848023.555084 depth/1341848023.555084.png
1341848023.586796 rgb/1341848023.586796.png 1341848023.586829 depth/1341848023.586829.png
1341848023.622845 rgb/1341848023.622845.png 1341848023.622864 depth/1341848023.622864.png
1341848023.687172 rgb/1341848023.687172.png 1341848023.687231 depth/1341848023.687231.png
1341848023.722693 rgb/1341848023.722693.png 1341848023.722722 depth/1341848023.722722.png
1341848023.754690 rgb/1341848023.754690.png 1341848023.754708 depth/1341848023.754708.png
1341848023.786854 rgb/1341848023.786854.png 1341848023.786872 depth/1341848023.786872.png
1341848023.822788 rgb/1341848023.822788.png 1341848023.822813 depth/1341848023.822813.png
1341848023.854825 rgb/1341848023.854825.png 1341848023.854837 depth/1341848023.854837.png
1341848023.890666 rgb/1341848023.890666.png 1341848023.891258 depth/1341848023.891258.png
1341848023.922784 rgb/1341848023.922784.png 1341848023.922935 depth/1341848023.922935.png
1341848023.954826 rgb/1341848023.954826.png 1341848023.955360 depth/1341848023.955360.png
1341848023.990739 rgb/1341848023.990739.png 1341848023.990753 depth/1341848023.990753.png
1341848024.022671 rgb/1341848024.022671.png 1341848024.022689 depth/1341848024.022689.png
1341848024.054725 rgb/1341848024.054725.png 1341848024.054737 depth/1341848024.054737.png
1341848024.122843 rgb/1341848024.122843.png 1341848024.122894 depth/1341848024.122894.png
1341848024.158762 rgb/1341848024.158762.png 1341848024.158798 depth/1341848024.158798.png
1341848024.190945 rgb/1341848024.190945.png 1341848024.190998 depth/1341848024.190998.png
1341848024.222838 rgb/1341848024.222838.png 1341848024.222850 depth/1341848024.222850.png
1341848024.258826 rgb/1341848024.258826.png 1341848024.258842 depth/1341848024.258842.png
1341848024.290769 rgb/1341848024.290769.png 1341848024.290872 depth/1341848024.290872.png
1341848024.322705 rgb/1341848024.322705.png 1341848024.322718 depth/1341848024.322718.png
1341848024.358743 rgb/1341848024.358743.png 1341848024.358801 depth/1341848024.358801.png
1341848024.390878 rgb/1341848024.390878.png 1341848024.391387 depth/1341848024.391387.png
1341848024.426783 rgb/1341848024.426783.png 1341848024.427236 depth/1341848024.427236.png
1341848024.458795 rgb/1341848024.458795.png 1341848024.458805 depth/1341848024.458805.png
1341848024.491019 rgb/1341848024.491019.png 1341848024.491036 depth/1341848024.491036.png
1341848024.526783 rgb/1341848024.526783.png 1341848024.526824 depth/1341848024.526824.png
1341848024.558627 rgb/1341848024.558627.png 1341848024.558650 depth/1341848024.558650.png
1341848024.594736 rgb/1341848024.594736.png 1341848024.594752 depth/1341848024.594752.png
1341848024.626657 rgb/1341848024.626657.png 1341848024.626676 depth/1341848024.626676.png
1341848024.658717 rgb/1341848024.658717.png 1341848024.658732 depth/1341848024.658732.png
1341848024.694820 rgb/1341848024.694820.png 1341848024.694844 depth/1341848024.694844.png
1341848024.727054 rgb/1341848024.727054.png 1341848024.727084 depth/1341848024.727084.png
1341848024.758938 rgb/1341848024.758938.png 1341848024.758959 depth/1341848024.758959.png
1341848024.794701 rgb/1341848024.794701.png 1341848024.794722 depth/1341848024.794722.png
1341848024.826727 rgb/1341848024.826727.png 1341848024.826800 depth/1341848024.826800.png
1341848024.862797 rgb/1341848024.862797.png 1341848024.862820 depth/1341848024.862820.png
1341848024.894777 rgb/1341848024.894777.png 1341848024.894797 depth/1341848024.894797.png
1341848024.926754 rgb/1341848024.926754.png 1341848024.927028 depth/1341848024.927028.png
1341848024.962678 rgb/1341848024.962678.png 1341848024.962751 depth/1341848024.962751.png
1341848024.994729 rgb/1341848024.994729.png 1341848024.994762 depth/1341848024.994762.png
1341848025.026872 rgb/1341848025.026872.png 1341848025.026914 depth/1341848025.026914.png
1341848025.062647 rgb/1341848025.062647.png 1341848025.062709 depth/1341848025.062709.png
1341848025.131056 rgb/1341848025.131056.png 1341848025.131097 depth/1341848025.131097.png
1341848025.163080 rgb/1341848025.163080.png 1341848025.167799 depth/1341848025.167799.png
1341848025.194910 rgb/1341848025.194910.png 1341848025.198408 depth/1341848025.198408.png
1341848025.230646 rgb/1341848025.230646.png 1341848025.230676 depth/1341848025.230676.png
1341848025.262679 rgb/1341848025.262679.png 1341848025.262716 depth/1341848025.262716.png
1341848025.294743 rgb/1341848025.294743.png 1341848025.294760 depth/1341848025.294760.png
1341848025.330653 rgb/1341848025.330653.png 1341848025.330673 depth/1341848025.330673.png
1341848025.363022 rgb/1341848025.363022.png 1341848025.363045 depth/1341848025.363045.png
1341848025.398825 rgb/1341848025.398825.png 1341848025.398864 depth/1341848025.398864.png
1341848025.430687 rgb/1341848025.430687.png 1341848025.430702 depth/1341848025.430702.png
1341848025.462832 rgb/1341848025.462832.png 1341848025.462851 depth/1341848025.462851.png
1341848025.498683 rgb/1341848025.498683.png 1341848025.498694 depth/1341848025.498694.png
1341848025.530800 rgb/1341848025.530800.png 1341848025.530813 depth/1341848025.530813.png
1341848025.566751 rgb/1341848025.566751.png 1341848025.566774 depth/1341848025.566774.png
1341848025.598738 rgb/1341848025.598738.png 1341848025.598755 depth/1341848025.598755.png
1341848025.630731 rgb/1341848025.630731.png 1341848025.630827 depth/1341848025.630827.png
1341848025.666677 rgb/1341848025.666677.png 1341848025.666699 depth/1341848025.666699.png
1341848025.698755 rgb/1341848025.698755.png 1341848025.698772 depth/1341848025.698772.png
1341848025.730719 rgb/1341848025.730719.png 1341848025.730736 depth/1341848025.730736.png
1341848025.766716 rgb/1341848025.766716.png 1341848025.766728 depth/1341848025.766728.png
1341848025.798909 rgb/1341848025.798909.png 1341848025.798965 depth/1341848025.798965.png
1341848025.834828 rgb/1341848025.834828.png 1341848025.834852 depth/1341848025.834852.png
1341848025.866679 rgb/1341848025.866679.png 1341848025.866702 depth/1341848025.866702.png
1341848025.898725 rgb/1341848025.898725.png 1341848025.898811 depth/1341848025.898811.png
1341848025.934824 rgb/1341848025.934824.png 1341848025.934850 depth/1341848025.934850.png
1341848025.967138 rgb/1341848025.967138.png 1341848025.967180 depth/1341848025.967180.png
1341848025.998679 rgb/1341848025.998679.png 1341848025.998763 depth/1341848025.998763.png
1341848026.034640 rgb/1341848026.034640.png 1341848026.034672 depth/1341848026.034672.png
1341848026.066857 rgb/1341848026.066857.png 1341848026.066885 depth/1341848026.066885.png
1341848026.102823 rgb/1341848026.102823.png 1341848026.102834 depth/1341848026.102834.png
1341848026.134670 rgb/1341848026.134670.png 1341848026.134679 depth/1341848026.134679.png
1341848026.166699 rgb/1341848026.166699.png 1341848026.167384 depth/1341848026.167384.png
1341848026.202754 rgb/1341848026.202754.png 1341848026.202788 depth/1341848026.202788.png
1341848026.234940 rgb/1341848026.234940.png 1341848026.234963 depth/1341848026.234963.png
1341848026.267001 rgb/1341848026.267001.png 1341848026.267027 depth/1341848026.267027.png
1341848026.302861 rgb/1341848026.302861.png 1341848026.302871 depth/1341848026.302871.png
1341848026.334824 rgb/1341848026.334824.png 1341848026.334861 depth/1341848026.334861.png
1341848026.371024 rgb/1341848026.371024.png 1341848026.371055 depth/1341848026.371055.png
1341848026.402725 rgb/1341848026.402725.png 1341848026.402746 depth/1341848026.402746.png
1341848026.434734 rgb/1341848026.434734.png 1341848026.434767 depth/1341848026.434767.png
1341848026.470839 rgb/1341848026.470839.png 1341848026.470906 depth/1341848026.470906.png
1341848026.502672 rgb/1341848026.502672.png 1341848026.502716 depth/1341848026.502716.png
1341848026.534739 rgb/1341848026.534739.png 1341848026.534781 depth/1341848026.534781.png
1341848026.570847 rgb/1341848026.570847.png 1341848026.570890 depth/1341848026.570890.png
1341848026.602721 rgb/1341848026.602721.png 1341848026.602778 depth/1341848026.602778.png
1341848026.641972 rgb/1341848026.641972.png 1341848026.642025 depth/1341848026.642025.png
1341848026.702795 rgb/1341848026.702795.png 1341848026.702812 depth/1341848026.702812.png
1341848026.738795 rgb/1341848026.738795.png 1341848026.738850 depth/1341848026.738850.png
1341848026.770813 rgb/1341848026.770813.png 1341848026.770822 depth/1341848026.770822.png
1341848026.806747 rgb/1341848026.806747.png 1341848026.806756 depth/1341848026.806756.png
1341848026.838668 rgb/1341848026.838668.png 1341848026.838685 depth/1341848026.838685.png
1341848026.878025 rgb/1341848026.878025.png 1341848026.878058 depth/1341848026.878058.png
1341848026.938881 rgb/1341848026.938881.png 1341848026.938914 depth/1341848026.938914.png
1341848026.970651 rgb/1341848026.970651.png 1341848026.970715 depth/1341848026.970715.png
1341848027.006815 rgb/1341848027.006815.png 1341848027.006847 depth/1341848027.006847.png
1341848027.038669 rgb/1341848027.038669.png 1341848027.038724 depth/1341848027.038724.png
1341848027.074785 rgb/1341848027.074785.png 1341848027.074808 depth/1341848027.074808.png
1341848027.106663 rgb/1341848027.106663.png 1341848027.106672 depth/1341848027.106672.png
1341848027.138671 rgb/1341848027.138671.png 1341848027.138707 depth/1341848027.138707.png
1341848027.174831 rgb/1341848027.174831.png 1341848027.174845 depth/1341848027.174845.png
1341848027.207212 rgb/1341848027.207212.png 1341848027.207228 depth/1341848027.207228.png
1341848027.238696 rgb/1341848027.238696.png 1341848027.238712 depth/1341848027.238712.png
1341848027.274701 rgb/1341848027.274701.png 1341848027.274713 depth/1341848027.274713.png
1341848027.306705 rgb/1341848027.306705.png 1341848027.306742 depth/1341848027.306742.png
1341848027.342775 rgb/1341848027.342775.png 1341848027.342833 depth/1341848027.342833.png
1341848027.374943 rgb/1341848027.374943.png 1341848027.374989 depth/1341848027.374989.png
1341848027.406837 rgb/1341848027.406837.png 1341848027.406863 depth/1341848027.406863.png
1341848027.442959 rgb/1341848027.442959.png 1341848027.442981 depth/1341848027.442981.png
1341848027.474800 rgb/1341848027.474800.png 1341848027.474828 depth/1341848027.474828.png
1341848027.506714 rgb/1341848027.506714.png 1341848027.506780 depth/1341848027.506780.png
1341848027.543310 rgb/1341848027.543310.png 1341848027.543335 depth/1341848027.543335.png
1341848027.574717 rgb/1341848027.574717.png 1341848027.575728 depth/1341848027.575728.png
1341848027.610716 rgb/1341848027.610716.png 1341848027.611142 depth/1341848027.611142.png
1341848027.642684 rgb/1341848027.642684.png 1341848027.643153 depth/1341848027.643153.png
1341848027.674731 rgb/1341848027.674731.png 1341848027.674775 depth/1341848027.674775.png
1341848027.711026 rgb/1341848027.711026.png 1341848027.711730 depth/1341848027.711730.png
1341848027.742789 rgb/1341848027.742789.png 1341848027.742804 depth/1341848027.742804.png
1341848027.778768 rgb/1341848027.778768.png 1341848027.778817 depth/1341848027.778817.png
1341848027.810746 rgb/1341848027.810746.png 1341848027.810851 depth/1341848027.810851.png
1341848027.842836 rgb/1341848027.842836.png 1341848027.842862 depth/1341848027.842862.png
1341848027.878669 rgb/1341848027.878669.png 1341848027.878682 depth/1341848027.878682.png
1341848027.911127 rgb/1341848027.911127.png 1341848027.911189 depth/1341848027.911189.png
1341848027.942732 rgb/1341848027.942732.png 1341848027.942760 depth/1341848027.942760.png
1341848027.978757 rgb/1341848027.978757.png 1341848027.978770 depth/1341848027.978770.png
1341848028.011034 rgb/1341848028.011034.png 1341848028.011132 depth/1341848028.011132.png
1341848028.046706 rgb/1341848028.046706.png 1341848028.046719 depth/1341848028.046719.png
1341848028.078967 rgb/1341848028.078967.png 1341848028.079918 depth/1341848028.079918.png
1341848028.110971 rgb/1341848028.110971.png 1341848028.112250 depth/1341848028.112250.png
1341848028.150637 rgb/1341848028.150637.png 1341848028.150704 depth/1341848028.150704.png
1341848028.186050 rgb/1341848028.186050.png 1341848028.187273 depth/1341848028.187273.png
1341848028.254235 rgb/1341848028.254235.png 1341848028.255491 depth/1341848028.255491.png
1341848028.314908 rgb/1341848028.314908.png 1341848028.315859 depth/1341848028.315859.png
1341848028.378956 rgb/1341848028.378956.png 1341848028.378974 depth/1341848028.378974.png
1341848028.414628 rgb/1341848028.414628.png 1341848028.415502 depth/1341848028.415502.png
1341848028.447632 rgb/1341848028.447632.png 1341848028.447654 depth/1341848028.447654.png
1341848028.482785 rgb/1341848028.482785.png 1341848028.483591 depth/1341848028.483591.png
1341848028.514701 rgb/1341848028.514701.png 1341848028.514716 depth/1341848028.514716.png
1341848028.546612 rgb/1341848028.546612.png 1341848028.546624 depth/1341848028.546624.png
1341848028.582747 rgb/1341848028.582747.png 1341848028.582765 depth/1341848028.582765.png
1341848028.614649 rgb/1341848028.614649.png 1341848028.614668 depth/1341848028.614668.png
1341848028.653766 rgb/1341848028.653766.png 1341848028.653785 depth/1341848028.653785.png
1341848028.721828 rgb/1341848028.721828.png 1341848028.721886 depth/1341848028.721886.png
1341848028.782861 rgb/1341848028.782861.png 1341848028.782881 depth/1341848028.782881.png
1341848028.814757 rgb/1341848028.814757.png 1341848028.814775 depth/1341848028.814775.png
1341848028.850773 rgb/1341848028.850773.png 1341848028.850785 depth/1341848028.850785.png
1341848028.882714 rgb/1341848028.882714.png 1341848028.882756 depth/1341848028.882756.png
1341848028.914838 rgb/1341848028.914838.png 1341848028.914857 depth/1341848028.914857.png
1341848028.950881 rgb/1341848028.950881.png 1341848028.951062 depth/1341848028.951062.png
1341848028.982690 rgb/1341848028.982690.png 1341848028.982706 depth/1341848028.982706.png
1341848029.018728 rgb/1341848029.018728.png 1341848029.018750 depth/1341848029.018750.png
1341848029.082877 rgb/1341848029.082877.png 1341848029.082899 depth/1341848029.082899.png
1341848029.118800 rgb/1341848029.118800.png 1341848029.118814 depth/1341848029.118814.png
1341848029.150715 rgb/1341848029.150715.png 1341848029.151467 depth/1341848029.151467.png
1341848029.182676 rgb/1341848029.182676.png 1341848029.182687 depth/1341848029.182687.png
1341848029.218708 rgb/1341848029.218708.png 1341848029.218723 depth/1341848029.218723.png
1341848029.250626 rgb/1341848029.250626.png 1341848029.250646 depth/1341848029.250646.png
1341848029.286969 rgb/1341848029.286969.png 1341848029.286988 depth/1341848029.286988.png
1341848029.320225 rgb/1341848029.320225.png 1341848029.320239 depth/1341848029.320239.png
1341848029.350954 rgb/1341848029.350954.png 1341848029.351197 depth/1341848029.351197.png
1341848029.386923 rgb/1341848029.386923.png 1341848029.386940 depth/1341848029.386940.png
1341848029.418757 rgb/1341848029.418757.png 1341848029.418775 depth/1341848029.418775.png
1341848029.450819 rgb/1341848029.450819.png 1341848029.450896 depth/1341848029.450896.png
1341848029.486788 rgb/1341848029.486788.png 1341848029.486809 depth/1341848029.486809.png
1341848029.518925 rgb/1341848029.518925.png 1341848029.519151 depth/1341848029.519151.png
1341848029.554721 rgb/1341848029.554721.png 1341848029.554734 depth/1341848029.554734.png
1341848029.586990 rgb/1341848029.586990.png 1341848029.587004 depth/1341848029.587004.png
1341848029.618715 rgb/1341848029.618715.png 1341848029.618729 depth/1341848029.618729.png
1341848029.655302 rgb/1341848029.655302.png 1341848029.655324 depth/1341848029.655324.png
1341848029.686830 rgb/1341848029.686830.png 1341848029.686905 depth/1341848029.686905.png
1341848029.718752 rgb/1341848029.718752.png 1341848029.718815 depth/1341848029.718815.png
1341848029.754791 rgb/1341848029.754791.png 1341848029.754809 depth/1341848029.754809.png
1341848029.786949 rgb/1341848029.786949.png 1341848029.787734 depth/1341848029.787734.png
1341848029.822778 rgb/1341848029.822778.png 1341848029.822795 depth/1341848029.822795.png
1341848029.854811 rgb/1341848029.854811.png 1341848029.854831 depth/1341848029.854831.png
1341848029.887992 rgb/1341848029.887992.png 1341848029.888015 depth/1341848029.888015.png
1341848029.922779 rgb/1341848029.922779.png 1341848029.923583 depth/1341848029.923583.png
1341848029.954640 rgb/1341848029.954640.png 1341848029.954654 depth/1341848029.954654.png
1341848029.990762 rgb/1341848029.990762.png 1341848029.990907 depth/1341848029.990907.png
1341848030.022873 rgb/1341848030.022873.png 1341848030.022894 depth/1341848030.022894.png
1341848030.054776 rgb/1341848030.054776.png 1341848030.054803 depth/1341848030.054803.png
1341848030.090782 rgb/1341848030.090782.png 1341848030.090796 depth/1341848030.090796.png
1341848030.122796 rgb/1341848030.122796.png 1341848030.122805 depth/1341848030.122805.png
1341848030.154918 rgb/1341848030.154918.png 1341848030.154932 depth/1341848030.154932.png
1341848030.190683 rgb/1341848030.190683.png 1341848030.190756 depth/1341848030.190756.png
1341848030.222713 rgb/1341848030.222713.png 1341848030.222780 depth/1341848030.222780.png
1341848030.258930 rgb/1341848030.258930.png 1341848030.258949 depth/1341848030.258949.png
1341848030.290864 rgb/1341848030.290864.png 1341848030.290914 depth/1341848030.290914.png
1341848030.322775 rgb/1341848030.322775.png 1341848030.323592 depth/1341848030.323592.png
1341848030.358886 rgb/1341848030.358886.png 1341848030.358972 depth/1341848030.358972.png
1341848030.390832 rgb/1341848030.390832.png 1341848030.390848 depth/1341848030.390848.png
1341848030.422795 rgb/1341848030.422795.png 1341848030.422812 depth/1341848030.422812.png
1341848030.458888 rgb/1341848030.458888.png 1341848030.458900 depth/1341848030.458900.png
1341848030.490846 rgb/1341848030.490846.png 1341848030.490939 depth/1341848030.490939.png
1341848030.526716 rgb/1341848030.526716.png 1341848030.526729 depth/1341848030.526729.png
1341848030.565795 rgb/1341848030.565795.png 1341848030.565858 depth/1341848030.565858.png
1341848030.626961 rgb/1341848030.626961.png 1341848030.627016 depth/1341848030.627016.png
1341848030.658903 rgb/1341848030.658903.png 1341848030.658937 depth/1341848030.658937.png
1341848030.690656 rgb/1341848030.690656.png 1341848030.690669 depth/1341848030.690669.png
1341848030.726765 rgb/1341848030.726765.png 1341848030.726776 depth/1341848030.726776.png
1341848030.758759 rgb/1341848030.758759.png 1341848030.758782 depth/1341848030.758782.png
1341848030.794692 rgb/1341848030.794692.png 1341848030.794790 depth/1341848030.794790.png
1341848030.827483 rgb/1341848030.827483.png 1341848030.827510 depth/1341848030.827510.png
1341848030.859838 rgb/1341848030.859838.png 1341848030.860076 depth/1341848030.860076.png
1341848030.894711 rgb/1341848030.894711.png 1341848030.894737 depth/1341848030.894737.png
1341848030.926741 rgb/1341848030.926741.png 1341848030.926760 depth/1341848030.926760.png
1341848030.958727 rgb/1341848030.958727.png 1341848030.958740 depth/1341848030.958740.png
1341848030.994735 rgb/1341848030.994735.png 1341848030.994752 depth/1341848030.994752.png
1341848031.026698 rgb/1341848031.026698.png 1341848031.026758 depth/1341848031.026758.png
1341848031.062783 rgb/1341848031.062783.png 1341848031.062796 depth/1341848031.062796.png
1341848031.094761 rgb/1341848031.094761.png 1341848031.094801 depth/1341848031.094801.png
1341848031.126776 rgb/1341848031.126776.png 1341848031.126837 depth/1341848031.126837.png
1341848031.162860 rgb/1341848031.162860.png 1341848031.162900 depth/1341848031.162900.png
1341848031.194685 rgb/1341848031.194685.png 1341848031.194721 depth/1341848031.194721.png
1341848031.230953 rgb/1341848031.230953.png 1341848031.231582 depth/1341848031.231582.png
1341848031.262715 rgb/1341848031.262715.png 1341848031.262738 depth/1341848031.262738.png
1341848031.294747 rgb/1341848031.294747.png 1341848031.294789 depth/1341848031.294789.png
1341848031.330754 rgb/1341848031.330754.png 1341848031.330775 depth/1341848031.330775.png
1341848031.363008 rgb/1341848031.363008.png 1341848031.363880 depth/1341848031.363880.png
1341848031.394753 rgb/1341848031.394753.png 1341848031.394778 depth/1341848031.394778.png
1341848031.430611 rgb/1341848031.430611.png 1341848031.430627 depth/1341848031.430627.png
1341848031.472150 rgb/1341848031.472150.png 1341848031.472171 depth/1341848031.472171.png
1341848031.502110 rgb/1341848031.502110.png 1341848031.502139 depth/1341848031.502139.png
1341848031.562876 rgb/1341848031.562876.png 1341848031.562937 depth/1341848031.562937.png
1341848031.598730 rgb/1341848031.598730.png 1341848031.598770 depth/1341848031.598770.png
1341848031.630816 rgb/1341848031.630816.png 1341848031.630831 depth/1341848031.630831.png
1341848031.662784 rgb/1341848031.662784.png 1341848031.663486 depth/1341848031.663486.png
1341848031.698757 rgb/1341848031.698757.png 1341848031.698824 depth/1341848031.698824.png
1341848031.730668 rgb/1341848031.730668.png 1341848031.730691 depth/1341848031.730691.png
1341848031.766658 rgb/1341848031.766658.png 1341848031.766694 depth/1341848031.766694.png
1341848031.798743 rgb/1341848031.798743.png 1341848031.798754 depth/1341848031.798754.png
1341848031.830821 rgb/1341848031.830821.png 1341848031.831520 depth/1341848031.831520.png
1341848031.866735 rgb/1341848031.866735.png 1341848031.866772 depth/1341848031.866772.png
1341848031.898722 rgb/1341848031.898722.png 1341848031.898737 depth/1341848031.898737.png
1341848031.930844 rgb/1341848031.930844.png 1341848031.931492 depth/1341848031.931492.png
1341848031.966694 rgb/1341848031.966694.png 1341848031.966709 depth/1341848031.966709.png
1341848031.998742 rgb/1341848031.998742.png 1341848031.998759 depth/1341848031.998759.png
1341848032.034711 rgb/1341848032.034711.png 1341848032.034732 depth/1341848032.034732.png
1341848032.066718 rgb/1341848032.066718.png 1341848032.066736 depth/1341848032.066736.png
1341848032.098732 rgb/1341848032.098732.png 1341848032.098745 depth/1341848032.098745.png
1341848032.134739 rgb/1341848032.134739.png 1341848032.134784 depth/1341848032.134784.png
1341848032.166964 rgb/1341848032.166964.png 1341848032.166979 depth/1341848032.166979.png
1341848032.203043 rgb/1341848032.203043.png 1341848032.203097 depth/1341848032.203097.png
1341848032.234663 rgb/1341848032.234663.png 1341848032.234711 depth/1341848032.234711.png
1341848032.266730 rgb/1341848032.266730.png 1341848032.266756 depth/1341848032.266756.png
1341848032.302842 rgb/1341848032.302842.png 1341848032.302891 depth/1341848032.302891.png
1341848032.334617 rgb/1341848032.334617.png 1341848032.334681 depth/1341848032.334681.png
1341848032.366699 rgb/1341848032.366699.png 1341848032.367298 depth/1341848032.367298.png
1341848032.402980 rgb/1341848032.402980.png 1341848032.402996 depth/1341848032.402996.png
1341848032.434730 rgb/1341848032.434730.png 1341848032.434774 depth/1341848032.434774.png
1341848032.470791 rgb/1341848032.470791.png 1341848032.470848 depth/1341848032.470848.png
1341848032.502972 rgb/1341848032.502972.png 1341848032.502987 depth/1341848032.502987.png
1341848032.534733 rgb/1341848032.534733.png 1341848032.534750 depth/1341848032.534750.png
1341848032.570910 rgb/1341848032.570910.png 1341848032.570937 depth/1341848032.570937.png
1341848032.603044 rgb/1341848032.603044.png 1341848032.603067 depth/1341848032.603067.png
1341848032.634746 rgb/1341848032.634746.png 1341848032.634766 depth/1341848032.634766.png
1341848032.670780 rgb/1341848032.670780.png 1341848032.670791 depth/1341848032.670791.png
1341848032.702791 rgb/1341848032.702791.png 1341848032.702808 depth/1341848032.702808.png
1341848032.738725 rgb/1341848032.738725.png 1341848032.738747 depth/1341848032.738747.png
1341848032.770741 rgb/1341848032.770741.png 1341848032.770781 depth/1341848032.770781.png
1341848032.802941 rgb/1341848032.802941.png 1341848032.803038 depth/1341848032.803038.png
1341848032.838781 rgb/1341848032.838781.png 1341848032.838796 depth/1341848032.838796.png
1341848032.870732 rgb/1341848032.870732.png 1341848032.870753 depth/1341848032.870753.png
1341848032.902707 rgb/1341848032.902707.png 1341848032.902950 depth/1341848032.902950.png
1341848032.938845 rgb/1341848032.938845.png 1341848032.938895 depth/1341848032.938895.png
1341848032.970816 rgb/1341848032.970816.png 1341848032.970839 depth/1341848032.970839.png
1341848033.006687 rgb/1341848033.006687.png 1341848033.006708 depth/1341848033.006708.png
1341848033.039238 rgb/1341848033.039238.png 1341848033.039254 depth/1341848033.039254.png
1341848033.070841 rgb/1341848033.070841.png 1341848033.070860 depth/1341848033.070860.png
1341848033.106948 rgb/1341848033.106948.png 1341848033.106966 depth/1341848033.106966.png
1341848033.139110 rgb/1341848033.139110.png 1341848033.139123 depth/1341848033.139123.png
1341848033.170741 rgb/1341848033.170741.png 1341848033.170754 depth/1341848033.170754.png
1341848033.206854 rgb/1341848033.206854.png 1341848033.206871 depth/1341848033.206871.png
1341848033.238728 rgb/1341848033.238728.png 1341848033.239415 depth/1341848033.239415.png
1341848033.274940 rgb/1341848033.274940.png 1341848033.274956 depth/1341848033.274956.png
1341848033.306665 rgb/1341848033.306665.png 1341848033.306706 depth/1341848033.306706.png
1341848033.338836 rgb/1341848033.338836.png 1341848033.338847 depth/1341848033.338847.png
1341848033.374810 rgb/1341848033.374810.png 1341848033.374830 depth/1341848033.374830.png
1341848033.406805 rgb/1341848033.406805.png 1341848033.406820 depth/1341848033.406820.png
1341848033.443097 rgb/1341848033.443097.png 1341848033.443142 depth/1341848033.443142.png
1341848033.474671 rgb/1341848033.474671.png 1341848033.474682 depth/1341848033.474682.png
1341848033.506807 rgb/1341848033.506807.png 1341848033.506821 depth/1341848033.506821.png
1341848033.542876 rgb/1341848033.542876.png 1341848033.542898 depth/1341848033.542898.png
1341848033.574826 rgb/1341848033.574826.png 1341848033.575008 depth/1341848033.575008.png
1341848033.606870 rgb/1341848033.606870.png 1341848033.606896 depth/1341848033.606896.png
1341848033.642934 rgb/1341848033.642934.png 1341848033.642954 depth/1341848033.642954.png
1341848033.674924 rgb/1341848033.674924.png 1341848033.674937 depth/1341848033.674937.png
1341848033.710808 rgb/1341848033.710808.png 1341848033.710835 depth/1341848033.710835.png
1341848033.742797 rgb/1341848033.742797.png 1341848033.742812 depth/1341848033.742812.png
1341848033.774817 rgb/1341848033.774817.png 1341848033.774832 depth/1341848033.774832.png
1341848033.811114 rgb/1341848033.811114.png 1341848033.811932 depth/1341848033.811932.png
1341848033.842774 rgb/1341848033.842774.png 1341848033.842813 depth/1341848033.842813.png
1341848033.874878 rgb/1341848033.874878.png 1341848033.874896 depth/1341848033.874896.png
1341848033.911229 rgb/1341848033.911229.png 1341848033.911372 depth/1341848033.911372.png
1341848033.942752 rgb/1341848033.942752.png 1341848033.942768 depth/1341848033.942768.png
1341848033.978916 rgb/1341848033.978916.png 1341848033.978933 depth/1341848033.978933.png
1341848034.010755 rgb/1341848034.010755.png 1341848034.010820 depth/1341848034.010820.png
1341848034.042713 rgb/1341848034.042713.png 1341848034.042730 depth/1341848034.042730.png
1341848034.078802 rgb/1341848034.078802.png 1341848034.078815 depth/1341848034.078815.png
1341848034.110771 rgb/1341848034.110771.png 1341848034.110948 depth/1341848034.110948.png
1341848034.142710 rgb/1341848034.142710.png 1341848034.142724 depth/1341848034.142724.png
1341848034.178809 rgb/1341848034.178809.png 1341848034.178845 depth/1341848034.178845.png
1341848034.210696 rgb/1341848034.210696.png 1341848034.210706 depth/1341848034.210706.png
1341848034.246723 rgb/1341848034.246723.png 1341848034.246736 depth/1341848034.246736.png
1341848034.278739 rgb/1341848034.278739.png 1341848034.278759 depth/1341848034.278759.png
1341848034.318061 rgb/1341848034.318061.png 1341848034.318578 depth/1341848034.318578.png
1341848034.353785 rgb/1341848034.353785.png 1341848034.353802 depth/1341848034.353802.png
1341848034.386162 rgb/1341848034.386162.png 1341848034.386178 depth/1341848034.386178.png
1341848034.421769 rgb/1341848034.421769.png 1341848034.421782 depth/1341848034.421782.png
1341848034.453838 rgb/1341848034.453838.png 1341848034.454621 depth/1341848034.454621.png
1341848034.485678 rgb/1341848034.485678.png 1341848034.485690 depth/1341848034.485690.png
1341848034.521747 rgb/1341848034.521747.png 1341848034.521758 depth/1341848034.521758.png
1341848034.553684 rgb/1341848034.553684.png 1341848034.553808 depth/1341848034.553808.png
1341848034.585774 rgb/1341848034.585774.png 1341848034.585791 depth/1341848034.585791.png
1341848034.653784 rgb/1341848034.653784.png 1341848034.654020 depth/1341848034.654020.png
1341848034.715163 rgb/1341848034.715163.png 1341848034.715221 depth/1341848034.715221.png
1341848034.746742 rgb/1341848034.746742.png 1341848034.746757 depth/1341848034.746757.png
1341848034.782798 rgb/1341848034.782798.png 1341848034.782867 depth/1341848034.782867.png
1341848034.814737 rgb/1341848034.814737.png 1341848034.814783 depth/1341848034.814783.png
1341848034.846851 rgb/1341848034.846851.png 1341848034.846883 depth/1341848034.846883.png
1341848034.882707 rgb/1341848034.882707.png 1341848034.882748 depth/1341848034.882748.png
1341848034.914816 rgb/1341848034.914816.png 1341848034.914862 depth/1341848034.914862.png
1341848034.951491 rgb/1341848034.951491.png 1341848034.952538 depth/1341848034.952538.png
1341848034.983028 rgb/1341848034.983028.png 1341848034.983102 depth/1341848034.983102.png
1341848035.014942 rgb/1341848035.014942.png 1341848035.014963 depth/1341848035.014963.png
1341848035.050945 rgb/1341848035.050945.png 1341848035.051588 depth/1341848035.051588.png
1341848035.084295 rgb/1341848035.084295.png 1341848035.084843 depth/1341848035.084843.png
1341848035.118886 rgb/1341848035.118886.png 1341848035.119920 depth/1341848035.119920.png
1341848035.218946 rgb/1341848035.218946.png 1341848035.219021 depth/1341848035.219021.png
1341848035.284261 rgb/1341848035.284261.png 1341848035.284280 depth/1341848035.284280.png
1341848035.319914 rgb/1341848035.319914.png 1341848035.320216 depth/1341848035.320216.png
1341848035.350991 rgb/1341848035.350991.png 1341848035.351243 depth/1341848035.351243.png
1341848035.422709 rgb/1341848035.422709.png 1341848035.423486 depth/1341848035.423486.png
1341848035.486822 rgb/1341848035.486822.png 1341848035.486844 depth/1341848035.486844.png
1341848035.518623 rgb/1341848035.518623.png 1341848035.518643 depth/1341848035.518643.png
1341848035.550852 rgb/1341848035.550852.png 1341848035.550866 depth/1341848035.550866.png
1341848035.586716 rgb/1341848035.586716.png 1341848035.586745 depth/1341848035.586745.png
1341848035.618790 rgb/1341848035.618790.png 1341848035.619346 depth/1341848035.619346.png
1341848035.654654 rgb/1341848035.654654.png 1341848035.654670 depth/1341848035.654670.png
1341848035.686693 rgb/1341848035.686693.png 1341848035.686737 depth/1341848035.686737.png
1341848035.718791 rgb/1341848035.718791.png 1341848035.718808 depth/1341848035.718808.png
1341848035.755991 rgb/1341848035.755991.png 1341848035.756650 depth/1341848035.756650.png
1341848035.786729 rgb/1341848035.786729.png 1341848035.786744 depth/1341848035.786744.png
1341848035.818784 rgb/1341848035.818784.png 1341848035.818816 depth/1341848035.818816.png
1341848035.854701 rgb/1341848035.854701.png 1341848035.854749 depth/1341848035.854749.png
1341848035.886689 rgb/1341848035.886689.png 1341848035.886726 depth/1341848035.886726.png
1341848035.922832 rgb/1341848035.922832.png 1341848035.922862 depth/1341848035.922862.png
1341848035.954633 rgb/1341848035.954633.png 1341848035.954650 depth/1341848035.954650.png
1341848035.986741 rgb/1341848035.986741.png 1341848035.986765 depth/1341848035.986765.png
1341848036.022779 rgb/1341848036.022779.png 1341848036.022805 depth/1341848036.022805.png
1341848036.054911 rgb/1341848036.054911.png 1341848036.054940 depth/1341848036.054940.png
1341848036.087013 rgb/1341848036.087013.png 1341848036.087039 depth/1341848036.087039.png
1341848036.122737 rgb/1341848036.122737.png 1341848036.122749 depth/1341848036.122749.png
1341848036.154810 rgb/1341848036.154810.png 1341848036.154843 depth/1341848036.154843.png
1341848036.190835 rgb/1341848036.190835.png 1341848036.190873 depth/1341848036.190873.png
1341848036.223282 rgb/1341848036.223282.png 1341848036.223325 depth/1341848036.223325.png
1341848036.254692 rgb/1341848036.254692.png 1341848036.254719 depth/1341848036.254719.png
1341848036.290758 rgb/1341848036.290758.png 1341848036.290792 depth/1341848036.290792.png
1341848036.354859 rgb/1341848036.354859.png 1341848036.354932 depth/1341848036.354932.png
1341848036.390843 rgb/1341848036.390843.png 1341848036.390859 depth/1341848036.390859.png
1341848036.458823 rgb/1341848036.458823.png 1341848036.458857 depth/1341848036.458857.png
1341848036.491205 rgb/1341848036.491205.png 1341848036.491256 depth/1341848036.491256.png
1341848036.522726 rgb/1341848036.522726.png 1341848036.522744 depth/1341848036.522744.png
1341848036.558942 rgb/1341848036.558942.png 1341848036.558959 depth/1341848036.558959.png
1341848036.590723 rgb/1341848036.590723.png 1341848036.590845 depth/1341848036.590845.png
1341848036.626802 rgb/1341848036.626802.png 1341848036.626814 depth/1341848036.626814.png
1341848036.658670 rgb/1341848036.658670.png 1341848036.659276 depth/1341848036.659276.png
1341848036.691175 rgb/1341848036.691175.png 1341848036.691212 depth/1341848036.691212.png
1341848036.726753 rgb/1341848036.726753.png 1341848036.727207 depth/1341848036.727207.png
1341848036.758851 rgb/1341848036.758851.png 1341848036.758965 depth/1341848036.758965.png
1341848036.790720 rgb/1341848036.790720.png 1341848036.790795 depth/1341848036.790795.png
1341848036.826992 rgb/1341848036.826992.png 1341848036.827011 depth/1341848036.827011.png
1341848036.858633 rgb/1341848036.858633.png 1341848036.858692 depth/1341848036.858692.png
1341848036.926846 rgb/1341848036.926846.png 1341848036.926861 depth/1341848036.926861.png
1341848036.958725 rgb/1341848036.958725.png 1341848036.958741 depth/1341848036.958741.png
1341848036.994836 rgb/1341848036.994836.png 1341848036.994877 depth/1341848036.994877.png
1341848037.026790 rgb/1341848037.026790.png 1341848037.026816 depth/1341848037.026816.png
1341848037.061042 rgb/1341848037.061042.png 1341848037.061067 depth/1341848037.061067.png
1341848037.094661 rgb/1341848037.094661.png 1341848037.094704 depth/1341848037.094704.png
1341848037.126709 rgb/1341848037.126709.png 1341848037.126721 depth/1341848037.126721.png
1341848037.162789 rgb/1341848037.162789.png 1341848037.162827 depth/1341848037.162827.png
1341848037.194724 rgb/1341848037.194724.png 1341848037.194761 depth/1341848037.194761.png
1341848037.227032 rgb/1341848037.227032.png 1341848037.227067 depth/1341848037.227067.png
1341848037.263738 rgb/1341848037.263738.png 1341848037.263842 depth/1341848037.263842.png
1341848037.295192 rgb/1341848037.295192.png 1341848037.295209 depth/1341848037.295209.png
1341848037.326868 rgb/1341848037.326868.png 1341848037.326883 depth/1341848037.326883.png
1341848037.362746 rgb/1341848037.362746.png 1341848037.362781 depth/1341848037.362781.png
1341848037.395057 rgb/1341848037.395057.png 1341848037.395068 depth/1341848037.395068.png
1341848037.430946 rgb/1341848037.430946.png 1341848037.431014 depth/1341848037.431014.png
1341848037.462765 rgb/1341848037.462765.png 1341848037.462779 depth/1341848037.462779.png
1341848037.530725 rgb/1341848037.530725.png 1341848037.530750 depth/1341848037.530750.png
1341848037.562958 rgb/1341848037.562958.png 1341848037.562996 depth/1341848037.562996.png
1341848037.595756 rgb/1341848037.595756.png 1341848037.595772 depth/1341848037.595772.png
1341848037.630756 rgb/1341848037.630756.png 1341848037.631133 depth/1341848037.631133.png
1341848037.662669 rgb/1341848037.662669.png 1341848037.662683 depth/1341848037.662683.png
1341848037.698670 rgb/1341848037.698670.png 1341848037.698730 depth/1341848037.698730.png
1341848037.730964 rgb/1341848037.730964.png 1341848037.730978 depth/1341848037.730978.png
1341848037.769764 rgb/1341848037.769764.png 1341848037.769809 depth/1341848037.769809.png
1341848037.837792 rgb/1341848037.837792.png 1341848037.837827 depth/1341848037.837827.png
1341848037.898921 rgb/1341848037.898921.png 1341848037.898948 depth/1341848037.898948.png
1341848037.930939 rgb/1341848037.930939.png 1341848037.930977 depth/1341848037.930977.png
1341848037.966864 rgb/1341848037.966864.png 1341848037.966899 depth/1341848037.966899.png
1341848037.998629 rgb/1341848037.998629.png 1341848037.998697 depth/1341848037.998697.png
1341848038.030908 rgb/1341848038.030908.png 1341848038.030940 depth/1341848038.030940.png
1341848038.066849 rgb/1341848038.066849.png 1341848038.066878 depth/1341848038.066878.png
1341848038.098674 rgb/1341848038.098674.png 1341848038.098693 depth/1341848038.098693.png
1341848038.134662 rgb/1341848038.134662.png 1341848038.134674 depth/1341848038.134674.png
1341848038.166674 rgb/1341848038.166674.png 1341848038.166692 depth/1341848038.166692.png
1341848038.198711 rgb/1341848038.198711.png 1341848038.198737 depth/1341848038.198737.png
1341848038.234726 rgb/1341848038.234726.png 1341848038.234752 depth/1341848038.234752.png
1341848038.274093 rgb/1341848038.274093.png 1341848038.274266 depth/1341848038.274266.png
1341848038.306525 rgb/1341848038.306525.png 1341848038.306668 depth/1341848038.306668.png
1341848038.341933 rgb/1341848038.341933.png 1341848038.341971 depth/1341848038.341971.png
1341848038.374117 rgb/1341848038.374117.png 1341848038.374124 depth/1341848038.374124.png
1341848038.409802 rgb/1341848038.409802.png 1341848038.409820 depth/1341848038.409820.png
1341848038.441825 rgb/1341848038.441825.png 1341848038.442214 depth/1341848038.442214.png
1341848038.473889 rgb/1341848038.473889.png 1341848038.473912 depth/1341848038.473912.png
1341848038.510185 rgb/1341848038.510185.png 1341848038.510216 depth/1341848038.510216.png
1341848038.566862 rgb/1341848038.566862.png 1341848038.566894 depth/1341848038.566894.png
1341848038.602989 rgb/1341848038.602989.png 1341848038.603019 depth/1341848038.603019.png
1341848038.634739 rgb/1341848038.634739.png 1341848038.634757 depth/1341848038.634757.png
1341848038.670685 rgb/1341848038.670685.png 1341848038.670717 depth/1341848038.670717.png
1341848038.702868 rgb/1341848038.702868.png 1341848038.702904 depth/1341848038.702904.png
1341848038.734794 rgb/1341848038.734794.png 1341848038.734810 depth/1341848038.734810.png
1341848038.770741 rgb/1341848038.770741.png 1341848038.770771 depth/1341848038.770771.png
1341848038.802800 rgb/1341848038.802800.png 1341848038.802827 depth/1341848038.802827.png
1341848038.838770 rgb/1341848038.838770.png 1341848038.838789 depth/1341848038.838789.png
1341848038.871141 rgb/1341848038.871141.png 1341848038.871181 depth/1341848038.871181.png
1341848038.902781 rgb/1341848038.902781.png 1341848038.903335 depth/1341848038.903335.png
1341848038.938767 rgb/1341848038.938767.png 1341848038.938797 depth/1341848038.938797.png
1341848038.970765 rgb/1341848038.970765.png 1341848038.970800 depth/1341848038.970800.png
1341848039.002634 rgb/1341848039.002634.png 1341848039.002655 depth/1341848039.002655.png
1341848039.038895 rgb/1341848039.038895.png 1341848039.038923 depth/1341848039.038923.png
1341848039.070805 rgb/1341848039.070805.png 1341848039.070823 depth/1341848039.070823.png
1341848039.106775 rgb/1341848039.106775.png 1341848039.106791 depth/1341848039.106791.png
1341848039.138656 rgb/1341848039.138656.png 1341848039.138659 depth/1341848039.138659.png
1341848039.170737 rgb/1341848039.170737.png 1341848039.170769 depth/1341848039.170769.png
1341848039.206814 rgb/1341848039.206814.png 1341848039.206838 depth/1341848039.206838.png
1341848039.238881 rgb/1341848039.238881.png 1341848039.239191 depth/1341848039.239191.png
1341848039.270959 rgb/1341848039.270959.png 1341848039.270979 depth/1341848039.270979.png
1341848039.306747 rgb/1341848039.306747.png 1341848039.306767 depth/1341848039.306767.png
1341848039.338889 rgb/1341848039.338889.png 1341848039.338904 depth/1341848039.338904.png
1341848039.374766 rgb/1341848039.374766.png 1341848039.375554 depth/1341848039.375554.png
1341848039.406886 rgb/1341848039.406886.png 1341848039.407826 depth/1341848039.407826.png
1341848039.438853 rgb/1341848039.438853.png 1341848039.438869 depth/1341848039.438869.png
1341848039.474867 rgb/1341848039.474867.png 1341848039.474885 depth/1341848039.474885.png
1341848039.507121 rgb/1341848039.507121.png 1341848039.508068 depth/1341848039.508068.png
1341848039.538659 rgb/1341848039.538659.png 1341848039.538673 depth/1341848039.538673.png
1341848039.574890 rgb/1341848039.574890.png 1341848039.574934 depth/1341848039.574934.png
1341848039.606721 rgb/1341848039.606721.png 1341848039.606737 depth/1341848039.606737.png
1341848039.642714 rgb/1341848039.642714.png 1341848039.642732 depth/1341848039.642732.png
1341848039.674760 rgb/1341848039.674760.png 1341848039.674771 depth/1341848039.674771.png
1341848039.707168 rgb/1341848039.707168.png 1341848039.707178 depth/1341848039.707178.png
1341848039.742862 rgb/1341848039.742862.png 1341848039.743701 depth/1341848039.743701.png
1341848039.775334 rgb/1341848039.775334.png 1341848039.775351 depth/1341848039.775351.png
1341848039.806875 rgb/1341848039.806875.png 1341848039.807101 depth/1341848039.807101.png
1341848039.843282 rgb/1341848039.843282.png 1341848039.843291 depth/1341848039.843291.png
1341848039.881803 rgb/1341848039.881803.png 1341848039.881841 depth/1341848039.881841.png
1341848039.943367 rgb/1341848039.943367.png 1341848039.943397 depth/1341848039.943397.png
1341848039.974815 rgb/1341848039.974815.png 1341848039.974838 depth/1341848039.974838.png
1341848040.010707 rgb/1341848040.010707.png 1341848040.010730 depth/1341848040.010730.png
1341848040.042768 rgb/1341848040.042768.png 1341848040.042790 depth/1341848040.042790.png
1341848040.078716 rgb/1341848040.078716.png 1341848040.078739 depth/1341848040.078739.png
1341848040.110819 rgb/1341848040.110819.png 1341848040.110865 depth/1341848040.110865.png
1341848040.142744 rgb/1341848040.142744.png 1341848040.142781 depth/1341848040.142781.png
1341848040.178810 rgb/1341848040.178810.png 1341848040.178825 depth/1341848040.178825.png
1341848040.211029 rgb/1341848040.211029.png 1341848040.211044 depth/1341848040.211044.png
1341848040.242681 rgb/1341848040.242681.png 1341848040.242703 depth/1341848040.242703.png
1341848040.278950 rgb/1341848040.278950.png 1341848040.278972 depth/1341848040.278972.png
1341848040.310719 rgb/1341848040.310719.png 1341848040.310730 depth/1341848040.310730.png
1341848040.346920 rgb/1341848040.346920.png 1341848040.346941 depth/1341848040.346941.png
1341848040.378809 rgb/1341848040.378809.png 1341848040.378824 depth/1341848040.378824.png
1341848040.410884 rgb/1341848040.410884.png 1341848040.410915 depth/1341848040.410915.png
1341848040.446720 rgb/1341848040.446720.png 1341848040.446754 depth/1341848040.446754.png
1341848040.478680 rgb/1341848040.478680.png 1341848040.478753 depth/1341848040.478753.png
1341848040.517796 rgb/1341848040.517796.png 1341848040.510881 depth/1341848040.510881.png
1341848040.578879 rgb/1341848040.578879.png 1341848040.578922 depth/1341848040.578922.png
1341848040.614917 rgb/1341848040.614917.png 1341848040.614969 depth/1341848040.614969.png
1341848040.646758 rgb/1341848040.646758.png 1341848040.646773 depth/1341848040.646773.png
1341848040.679034 rgb/1341848040.679034.png 1341848040.679046 depth/1341848040.679046.png
1341848040.714653 rgb/1341848040.714653.png 1341848040.714664 depth/1341848040.714664.png
1341848040.746821 rgb/1341848040.746821.png 1341848040.746831 depth/1341848040.746831.png
1341848040.778774 rgb/1341848040.778774.png 1341848040.778786 depth/1341848040.778786.png
1341848040.814675 rgb/1341848040.814675.png 1341848040.814687 depth/1341848040.814687.png
1341848040.846908 rgb/1341848040.846908.png 1341848040.846924 depth/1341848040.846924.png
1341848040.882827 rgb/1341848040.882827.png 1341848040.883358 depth/1341848040.883358.png
1341848040.914699 rgb/1341848040.914699.png 1341848040.914798 depth/1341848040.914798.png
1341848040.946862 rgb/1341848040.946862.png 1341848040.946870 depth/1341848040.946870.png
1341848040.984484 rgb/1341848040.984484.png 1341848040.985270 depth/1341848040.985270.png
1341848041.022638 rgb/1341848041.022638.png 1341848041.023937 depth/1341848041.023937.png
1341848041.058859 rgb/1341848041.058859.png 1341848041.058889 depth/1341848041.058889.png
1341848041.094347 rgb/1341848041.094347.png 1341848041.095717 depth/1341848041.095717.png
1341848041.122188 rgb/1341848041.122188.png 1341848041.122200 depth/1341848041.122200.png
1341848041.189954 rgb/1341848041.189954.png 1341848041.189991 depth/1341848041.189991.png
1341848041.250726 rgb/1341848041.250726.png 1341848041.250741 depth/1341848041.250741.png
1341848041.283054 rgb/1341848041.283054.png 1341848041.284122 depth/1341848041.284122.png
1341848041.319290 rgb/1341848041.319290.png 1341848041.320300 depth/1341848041.320300.png
1341848041.355465 rgb/1341848041.355465.png 1341848041.356564 depth/1341848041.356564.png
1341848041.384901 rgb/1341848041.384901.png 1341848041.385925 depth/1341848041.385925.png
1341848041.418768 rgb/1341848041.418768.png 1341848041.418779 depth/1341848041.418779.png
1341848041.450845 rgb/1341848041.450845.png 1341848041.451522 depth/1341848041.451522.png
1341848041.482801 rgb/1341848041.482801.png 1341848041.483609 depth/1341848041.483609.png
1341848041.518788 rgb/1341848041.518788.png 1341848041.519116 depth/1341848041.519116.png
1341848041.550730 rgb/1341848041.550730.png 1341848041.551098 depth/1341848041.551098.png
1341848041.586805 rgb/1341848041.586805.png 1341848041.586822 depth/1341848041.586822.png
1341848041.618743 rgb/1341848041.618743.png 1341848041.618759 depth/1341848041.618759.png
1341848041.650957 rgb/1341848041.650957.png 1341848041.650973 depth/1341848041.650973.png
1341848041.686781 rgb/1341848041.686781.png 1341848041.686793 depth/1341848041.686793.png
1341848041.718789 rgb/1341848041.718789.png 1341848041.718845 depth/1341848041.718845.png
1341848041.750776 rgb/1341848041.750776.png 1341848041.750796 depth/1341848041.750796.png
1341848041.786711 rgb/1341848041.786711.png 1341848041.786723 depth/1341848041.786723.png
1341848041.818704 rgb/1341848041.818704.png 1341848041.818714 depth/1341848041.818714.png
1341848041.854747 rgb/1341848041.854747.png 1341848041.854755 depth/1341848041.854755.png
1341848041.886710 rgb/1341848041.886710.png 1341848041.886728 depth/1341848041.886728.png
1341848041.918718 rgb/1341848041.918718.png 1341848041.918730 depth/1341848041.918730.png
1341848041.994975 rgb/1341848041.994975.png 1341848041.986734 depth/1341848041.986734.png
1341848042.018871 rgb/1341848042.018871.png 1341848042.019582 depth/1341848042.019582.png
1341848042.054627 rgb/1341848042.054627.png 1341848042.054650 depth/1341848042.054650.png
1341848042.089498 rgb/1341848042.089498.png 1341848042.089516 depth/1341848042.089516.png
1341848042.122881 rgb/1341848042.122881.png 1341848042.122905 depth/1341848042.122905.png
1341848042.154788 rgb/1341848042.154788.png 1341848042.154807 depth/1341848042.154807.png
1341848042.186714 rgb/1341848042.186714.png 1341848042.186794 depth/1341848042.186794.png
1341848042.222883 rgb/1341848042.222883.png 1341848042.222915 depth/1341848042.222915.png
1341848042.254762 rgb/1341848042.254762.png 1341848042.254771 depth/1341848042.254771.png
1341848042.290694 rgb/1341848042.290694.png 1341848042.290712 depth/1341848042.290712.png
1341848042.322759 rgb/1341848042.322759.png 1341848042.322792 depth/1341848042.322792.png
1341848042.354987 rgb/1341848042.354987.png 1341848042.355022 depth/1341848042.355022.png
1341848042.390711 rgb/1341848042.390711.png 1341848042.390726 depth/1341848042.390726.png
1341848042.429737 rgb/1341848042.429737.png 1341848042.429783 depth/1341848042.429783.png
1341848042.490921 rgb/1341848042.490921.png 1341848042.490969 depth/1341848042.490969.png
1341848042.522713 rgb/1341848042.522713.png 1341848042.522727 depth/1341848042.522727.png
1341848042.558691 rgb/1341848042.558691.png 1341848042.558699 depth/1341848042.558699.png
1341848042.590841 rgb/1341848042.590841.png 1341848042.590860 depth/1341848042.590860.png
1341848042.622730 rgb/1341848042.622730.png 1341848042.622787 depth/1341848042.622787.png
1341848042.658741 rgb/1341848042.658741.png 1341848042.658766 depth/1341848042.658766.png
1341848042.697779 rgb/1341848042.697779.png 1341848042.697819 depth/1341848042.697819.png
1341848042.729778 rgb/1341848042.729778.png 1341848042.729807 depth/1341848042.729807.png
1341848042.761637 rgb/1341848042.761637.png 1341848042.761653 depth/1341848042.761653.png
1341848042.797954 rgb/1341848042.797954.png 1341848042.797965 depth/1341848042.797965.png
1341848042.829708 rgb/1341848042.829708.png 1341848042.829769 depth/1341848042.829769.png
1341848042.861726 rgb/1341848042.861726.png 1341848042.861744 depth/1341848042.861744.png
1341848042.897767 rgb/1341848042.897767.png 1341848042.897784 depth/1341848042.897784.png
1341848042.929860 rgb/1341848042.929860.png 1341848042.929876 depth/1341848042.929876.png
1341848042.965708 rgb/1341848042.965708.png 1341848042.965723 depth/1341848042.965723.png
1341848042.997994 rgb/1341848042.997994.png 1341848042.998639 depth/1341848042.998639.png
1341848043.030335 rgb/1341848043.030335.png 1341848043.030388 depth/1341848043.030388.png
1341848043.065737 rgb/1341848043.065737.png 1341848043.065763 depth/1341848043.065763.png
1341848043.097862 rgb/1341848043.097862.png 1341848043.097882 depth/1341848043.097882.png
1341848043.133955 rgb/1341848043.133955.png 1341848043.133981 depth/1341848043.133981.png
1341848043.165792 rgb/1341848043.165792.png 1341848043.165803 depth/1341848043.165803.png
1341848043.201879 rgb/1341848043.201879.png 1341848043.201911 depth/1341848043.201911.png
1341848043.233861 rgb/1341848043.233861.png 1341848043.233874 depth/1341848043.233874.png
1341848043.265717 rgb/1341848043.265717.png 1341848043.265835 depth/1341848043.265835.png
1341848043.301798 rgb/1341848043.301798.png 1341848043.301842 depth/1341848043.301842.png
1341848043.334034 rgb/1341848043.334034.png 1341848043.334065 depth/1341848043.334065.png
1341848043.369819 rgb/1341848043.369819.png 1341848043.369863 depth/1341848043.369863.png
1341848043.401743 rgb/1341848043.401743.png 1341848043.401757 depth/1341848043.401757.png
1341848043.433949 rgb/1341848043.433949.png 1341848043.433974 depth/1341848043.433974.png
1341848043.469625 rgb/1341848043.469625.png 1341848043.469655 depth/1341848043.469655.png
1341848043.501696 rgb/1341848043.501696.png 1341848043.501719 depth/1341848043.501719.png
1341848043.537825 rgb/1341848043.537825.png 1341848043.537840 depth/1341848043.537840.png
1341848043.569664 rgb/1341848043.569664.png 1341848043.569696 depth/1341848043.569696.png
1341848043.601838 rgb/1341848043.601838.png 1341848043.601863 depth/1341848043.601863.png
1341848043.637798 rgb/1341848043.637798.png 1341848043.637825 depth/1341848043.637825.png
1341848043.670144 rgb/1341848043.670144.png 1341848043.670837 depth/1341848043.670837.png
1341848043.701979 rgb/1341848043.701979.png 1341848043.701997 depth/1341848043.701997.png
1341848043.737757 rgb/1341848043.737757.png 1341848043.738719 depth/1341848043.738719.png
1341848043.769828 rgb/1341848043.769828.png 1341848043.769854 depth/1341848043.769854.png
1341848043.805817 rgb/1341848043.805817.png 1341848043.805831 depth/1341848043.805831.png
1341848043.837855 rgb/1341848043.837855.png 1341848043.837882 depth/1341848043.837882.png
1341848043.869697 rgb/1341848043.869697.png 1341848043.870385 depth/1341848043.870385.png
1341848043.905731 rgb/1341848043.905731.png 1341848043.905743 depth/1341848043.905743.png
1341848043.938034 rgb/1341848043.938034.png 1341848043.938044 depth/1341848043.938044.png
1341848043.969826 rgb/1341848043.969826.png 1341848043.969839 depth/1341848043.969839.png
1341848044.005919 rgb/1341848044.005919.png 1341848044.005940 depth/1341848044.005940.png
1341848044.037703 rgb/1341848044.037703.png 1341848044.037722 depth/1341848044.037722.png
1341848044.073762 rgb/1341848044.073762.png 1341848044.073825 depth/1341848044.073825.png
1341848044.105804 rgb/1341848044.105804.png 1341848044.105831 depth/1341848044.105831.png
1341848044.137722 rgb/1341848044.137722.png 1341848044.137734 depth/1341848044.137734.png
1341848044.173825 rgb/1341848044.173825.png 1341848044.173851 depth/1341848044.173851.png
1341848044.205750 rgb/1341848044.205750.png 1341848044.205765 depth/1341848044.205765.png
1341848044.237767 rgb/1341848044.237767.png 1341848044.237808 depth/1341848044.237808.png
1341848044.273822 rgb/1341848044.273822.png 1341848044.273852 depth/1341848044.273852.png
1341848044.305742 rgb/1341848044.305742.png 1341848044.305751 depth/1341848044.305751.png
1341848044.337838 rgb/1341848044.337838.png 1341848044.338467 depth/1341848044.338467.png
1341848044.373688 rgb/1341848044.373688.png 1341848044.373771 depth/1341848044.373771.png
1341848044.405874 rgb/1341848044.405874.png 1341848044.406389 depth/1341848044.406389.png
1341848044.441696 rgb/1341848044.441696.png 1341848044.441804 depth/1341848044.441804.png
1341848044.473716 rgb/1341848044.473716.png 1341848044.473726 depth/1341848044.473726.png
1341848044.505687 rgb/1341848044.505687.png 1341848044.505703 depth/1341848044.505703.png
1341848044.541856 rgb/1341848044.541856.png 1341848044.541889 depth/1341848044.541889.png
1341848044.573760 rgb/1341848044.573760.png 1341848044.573776 depth/1341848044.573776.png
1341848044.605829 rgb/1341848044.605829.png 1341848044.605851 depth/1341848044.605851.png
1341848044.641741 rgb/1341848044.641741.png 1341848044.641753 depth/1341848044.641753.png
1341848044.705966 rgb/1341848044.705966.png 1341848044.706034 depth/1341848044.706034.png
1341848044.771011 rgb/1341848044.771011.png 1341848044.771614 depth/1341848044.771614.png
1341848044.802833 rgb/1341848044.802833.png 1341848044.803289 depth/1341848044.803289.png
1341848044.834852 rgb/1341848044.834852.png 1341848044.834869 depth/1341848044.834869.png
1341848044.870686 rgb/1341848044.870686.png 1341848044.870710 depth/1341848044.870710.png
1341848044.902692 rgb/1341848044.902692.png 1341848044.902865 depth/1341848044.902865.png
1341848044.970797 rgb/1341848044.970797.png 1341848044.970831 depth/1341848044.970831.png
1341848045.002641 rgb/1341848045.002641.png 1341848045.002657 depth/1341848045.002657.png
1341848045.038733 rgb/1341848045.038733.png 1341848045.038769 depth/1341848045.038769.png
1341848045.070849 rgb/1341848045.070849.png 1341848045.071339 depth/1341848045.071339.png
1341848045.102831 rgb/1341848045.102831.png 1341848045.102854 depth/1341848045.102854.png
1341848045.138762 rgb/1341848045.138762.png 1341848045.139311 depth/1341848045.139311.png
1341848045.170759 rgb/1341848045.170759.png 1341848045.170788 depth/1341848045.170788.png
1341848045.202698 rgb/1341848045.202698.png 1341848045.202711 depth/1341848045.202711.png
1341848045.238872 rgb/1341848045.238872.png 1341848045.238927 depth/1341848045.238927.png
1341848045.270833 rgb/1341848045.270833.png 1341848045.270857 depth/1341848045.270857.png
1341848045.306816 rgb/1341848045.306816.png 1341848045.306863 depth/1341848045.306863.png
1341848045.338698 rgb/1341848045.338698.png 1341848045.338809 depth/1341848045.338809.png
1341848045.370799 rgb/1341848045.370799.png 1341848045.370820 depth/1341848045.370820.png
1341848045.406703 rgb/1341848045.406703.png 1341848045.406744 depth/1341848045.406744.png
1341848045.438695 rgb/1341848045.438695.png 1341848045.438734 depth/1341848045.438734.png
1341848045.474692 rgb/1341848045.474692.png 1341848045.474832 depth/1341848045.474832.png
1341848045.538886 rgb/1341848045.538886.png 1341848045.538904 depth/1341848045.538904.png
1341848045.606920 rgb/1341848045.606920.png 1341848045.607002 depth/1341848045.607002.png
1341848045.645890 rgb/1341848045.645890.png 1341848045.645941 depth/1341848045.645941.png
1341848045.706968 rgb/1341848045.706968.png 1341848045.707020 depth/1341848045.707020.png
1341848045.743092 rgb/1341848045.743092.png 1341848045.743136 depth/1341848045.743136.png
1341848045.774776 rgb/1341848045.774776.png 1341848045.774792 depth/1341848045.774792.png
1341848045.807609 rgb/1341848045.807609.png 1341848045.807673 depth/1341848045.807673.png
1341848045.842865 rgb/1341848045.842865.png 1341848045.842900 depth/1341848045.842900.png
1341848045.874777 rgb/1341848045.874777.png 1341848045.875086 depth/1341848045.875086.png
1341848045.906765 rgb/1341848045.906765.png 1341848045.906846 depth/1341848045.906846.png
1341848045.942758 rgb/1341848045.942758.png 1341848045.942880 depth/1341848045.942880.png
1341848045.974768 rgb/1341848045.974768.png 1341848045.974792 depth/1341848045.974792.png
1341848046.010763 rgb/1341848046.010763.png 1341848046.010772 depth/1341848046.010772.png
1341848046.042828 rgb/1341848046.042828.png 1341848046.042856 depth/1341848046.042856.png
1341848046.074722 rgb/1341848046.074722.png 1341848046.074759 depth/1341848046.074759.png
1341848046.110817 rgb/1341848046.110817.png 1341848046.111023 depth/1341848046.111023.png
1341848046.142773 rgb/1341848046.142773.png 1341848046.142790 depth/1341848046.142790.png
1341848046.181848 rgb/1341848046.181848.png 1341848046.182775 depth/1341848046.182775.png
1341848046.219718 rgb/1341848046.219718.png 1341848046.219760 depth/1341848046.219760.png
1341848046.249730 rgb/1341848046.249730.png 1341848046.249758 depth/1341848046.249758.png
1341848046.283599 rgb/1341848046.283599.png 1341848046.284157 depth/1341848046.284157.png
1341848046.317731 rgb/1341848046.317731.png 1341848046.317760 depth/1341848046.317760.png
1341848046.349732 rgb/1341848046.349732.png 1341848046.349752 depth/1341848046.349752.png
1341848046.382309 rgb/1341848046.382309.png 1341848046.382801 depth/1341848046.382801.png
1341848046.417763 rgb/1341848046.417763.png 1341848046.417780 depth/1341848046.417780.png
1341848046.449782 rgb/1341848046.449782.png 1341848046.449814 depth/1341848046.449814.png
1341848046.485848 rgb/1341848046.485848.png 1341848046.485866 depth/1341848046.485866.png
1341848046.517760 rgb/1341848046.517760.png 1341848046.517776 depth/1341848046.517776.png
1341848046.549658 rgb/1341848046.549658.png 1341848046.549677 depth/1341848046.549677.png
1341848046.586076 rgb/1341848046.586076.png 1341848046.586113 depth/1341848046.586113.png
1341848046.617769 rgb/1341848046.617769.png 1341848046.617799 depth/1341848046.617799.png
1341848046.653748 rgb/1341848046.653748.png 1341848046.653760 depth/1341848046.653760.png
1341848046.714925 rgb/1341848046.714925.png 1341848046.715121 depth/1341848046.715121.png
1341848046.746888 rgb/1341848046.746888.png 1341848046.746904 depth/1341848046.746904.png
1341848046.778736 rgb/1341848046.778736.png 1341848046.778755 depth/1341848046.778755.png
1341848046.814747 rgb/1341848046.814747.png 1341848046.814769 depth/1341848046.814769.png
1341848046.846853 rgb/1341848046.846853.png 1341848046.846875 depth/1341848046.846875.png
1341848046.878793 rgb/1341848046.878793.png 1341848046.878814 depth/1341848046.878814.png
1341848046.915079 rgb/1341848046.915079.png 1341848046.915688 depth/1341848046.915688.png
1341848046.946882 rgb/1341848046.946882.png 1341848046.947809 depth/1341848046.947809.png
1341848046.982780 rgb/1341848046.982780.png 1341848046.983538 depth/1341848046.983538.png
1341848047.015086 rgb/1341848047.015086.png 1341848047.015187 depth/1341848047.015187.png
1341848047.047884 rgb/1341848047.047884.png 1341848047.047899 depth/1341848047.047899.png
1341848047.089866 rgb/1341848047.089866.png 1341848047.090622 depth/1341848047.090622.png
1341848047.147565 rgb/1341848047.147565.png 1341848047.148403 depth/1341848047.148403.png
1341848047.214887 rgb/1341848047.214887.png 1341848047.214908 depth/1341848047.214908.png
1341848047.250668 rgb/1341848047.250668.png 1341848047.250958 depth/1341848047.250958.png
1341848047.282779 rgb/1341848047.282779.png 1341848047.283384 depth/1341848047.283384.png
1341848047.314815 rgb/1341848047.314815.png 1341848047.314838 depth/1341848047.314838.png
1341848047.350637 rgb/1341848047.350637.png 1341848047.350663 depth/1341848047.350663.png
1341848047.383038 rgb/1341848047.383038.png 1341848047.383072 depth/1341848047.383072.png
1341848047.414781 rgb/1341848047.414781.png 1341848047.414794 depth/1341848047.414794.png
1341848047.450847 rgb/1341848047.450847.png 1341848047.450870 depth/1341848047.450870.png
1341848047.482648 rgb/1341848047.482648.png 1341848047.482683 depth/1341848047.482683.png
1341848047.518733 rgb/1341848047.518733.png 1341848047.518985 depth/1341848047.518985.png
1341848047.550836 rgb/1341848047.550836.png 1341848047.551401 depth/1341848047.551401.png
1341848047.582955 rgb/1341848047.582955.png 1341848047.582975 depth/1341848047.582975.png
1341848047.618981 rgb/1341848047.618981.png 1341848047.619010 depth/1341848047.619010.png
1341848047.650752 rgb/1341848047.650752.png 1341848047.650786 depth/1341848047.650786.png
1341848047.689728 rgb/1341848047.689728.png 1341848047.686710 depth/1341848047.686710.png
1341848047.750845 rgb/1341848047.750845.png 1341848047.750865 depth/1341848047.750865.png
1341848047.786695 rgb/1341848047.786695.png 1341848047.786706 depth/1341848047.786706.png
1341848047.818804 rgb/1341848047.818804.png 1341848047.818832 depth/1341848047.818832.png
1341848047.850811 rgb/1341848047.850811.png 1341848047.850844 depth/1341848047.850844.png
1341848047.886853 rgb/1341848047.886853.png 1341848047.886871 depth/1341848047.886871.png
1341848047.918858 rgb/1341848047.918858.png 1341848047.918881 depth/1341848047.918881.png
1341848047.954723 rgb/1341848047.954723.png 1341848047.954736 depth/1341848047.954736.png
1341848047.986771 rgb/1341848047.986771.png 1341848047.986794 depth/1341848047.986794.png
1341848048.018897 rgb/1341848048.018897.png 1341848048.019427 depth/1341848048.019427.png
1341848048.054937 rgb/1341848048.054937.png 1341848048.054958 depth/1341848048.054958.png
1341848048.086776 rgb/1341848048.086776.png 1341848048.086796 depth/1341848048.086796.png
1341848048.118790 rgb/1341848048.118790.png 1341848048.119190 depth/1341848048.119190.png
1341848048.154692 rgb/1341848048.154692.png 1341848048.154706 depth/1341848048.154706.png
1341848048.186720 rgb/1341848048.186720.png 1341848048.186737 depth/1341848048.186737.png
1341848048.222966 rgb/1341848048.222966.png 1341848048.222998 depth/1341848048.222998.png
1341848048.254953 rgb/1341848048.254953.png 1341848048.254981 depth/1341848048.254981.png
1341848048.286640 rgb/1341848048.286640.png 1341848048.286675 depth/1341848048.286675.png
1341848048.322843 rgb/1341848048.322843.png 1341848048.322868 depth/1341848048.322868.png
1341848048.354699 rgb/1341848048.354699.png 1341848048.354767 depth/1341848048.354767.png
1341848048.386709 rgb/1341848048.386709.png 1341848048.387170 depth/1341848048.387170.png
1341848048.422649 rgb/1341848048.422649.png 1341848048.422664 depth/1341848048.422664.png
1341848048.454923 rgb/1341848048.454923.png 1341848048.454947 depth/1341848048.454947.png
1341848048.490668 rgb/1341848048.490668.png 1341848048.490748 depth/1341848048.490748.png
1341848048.522793 rgb/1341848048.522793.png 1341848048.522819 depth/1341848048.522819.png
1341848048.554990 rgb/1341848048.554990.png 1341848048.555714 depth/1341848048.555714.png
1341848048.590630 rgb/1341848048.590630.png 1341848048.590665 depth/1341848048.590665.png
1341848048.622652 rgb/1341848048.622652.png 1341848048.622669 depth/1341848048.622669.png
1341848048.658741 rgb/1341848048.658741.png 1341848048.658771 depth/1341848048.658771.png
1341848048.690791 rgb/1341848048.690791.png 1341848048.690804 depth/1341848048.690804.png
1341848048.722708 rgb/1341848048.722708.png 1341848048.722725 depth/1341848048.722725.png
1341848048.758833 rgb/1341848048.758833.png 1341848048.758865 depth/1341848048.758865.png
1341848048.791156 rgb/1341848048.791156.png 1341848048.791827 depth/1341848048.791827.png
1341848048.822736 rgb/1341848048.822736.png 1341848048.822751 depth/1341848048.822751.png
1341848048.858661 rgb/1341848048.858661.png 1341848048.858682 depth/1341848048.858682.png
1341848048.891041 rgb/1341848048.891041.png 1341848048.891115 depth/1341848048.891115.png
1341848048.926768 rgb/1341848048.926768.png 1341848048.926806 depth/1341848048.926806.png
1341848048.958953 rgb/1341848048.958953.png 1341848048.958976 depth/1341848048.958976.png
1341848048.990810 rgb/1341848048.990810.png 1341848048.990852 depth/1341848048.990852.png
1341848049.026707 rgb/1341848049.026707.png 1341848049.026726 depth/1341848049.026726.png
1341848049.058792 rgb/1341848049.058792.png 1341848049.058854 depth/1341848049.058854.png
1341848049.090709 rgb/1341848049.090709.png 1341848049.090734 depth/1341848049.090734.png
1341848049.126753 rgb/1341848049.126753.png 1341848049.126771 depth/1341848049.126771.png
1341848049.158854 rgb/1341848049.158854.png 1341848049.158868 depth/1341848049.158868.png
1341848049.194708 rgb/1341848049.194708.png 1341848049.194728 depth/1341848049.194728.png
1341848049.226742 rgb/1341848049.226742.png 1341848049.226785 depth/1341848049.226785.png
1341848049.258792 rgb/1341848049.258792.png 1341848049.258839 depth/1341848049.258839.png
1341848049.294747 rgb/1341848049.294747.png 1341848049.294771 depth/1341848049.294771.png
1341848049.326837 rgb/1341848049.326837.png 1341848049.326876 depth/1341848049.326876.png
1341848049.358802 rgb/1341848049.358802.png 1341848049.358834 depth/1341848049.358834.png
1341848049.394779 rgb/1341848049.394779.png 1341848049.394804 depth/1341848049.394804.png
1341848049.426763 rgb/1341848049.426763.png 1341848049.427229 depth/1341848049.427229.png
1341848049.462746 rgb/1341848049.462746.png 1341848049.462781 depth/1341848049.462781.png
1341848049.494728 rgb/1341848049.494728.png 1341848049.494750 depth/1341848049.494750.png
1341848049.526803 rgb/1341848049.526803.png 1341848049.526823 depth/1341848049.526823.png
1341848049.562799 rgb/1341848049.562799.png 1341848049.562822 depth/1341848049.562822.png
1341848049.594759 rgb/1341848049.594759.png 1341848049.594778 depth/1341848049.594778.png
1341848049.626829 rgb/1341848049.626829.png 1341848049.626847 depth/1341848049.626847.png
1341848049.662690 rgb/1341848049.662690.png 1341848049.662727 depth/1341848049.662727.png
1341848049.695064 rgb/1341848049.695064.png 1341848049.695078 depth/1341848049.695078.png
1341848049.730793 rgb/1341848049.730793.png 1341848049.730887 depth/1341848049.730887.png
1341848049.762702 rgb/1341848049.762702.png 1341848049.763163 depth/1341848049.763163.png
1341848049.794722 rgb/1341848049.794722.png 1341848049.794771 depth/1341848049.794771.png
1341848049.830816 rgb/1341848049.830816.png 1341848049.830836 depth/1341848049.830836.png
1341848049.869834 rgb/1341848049.869834.png 1341848049.862754 depth/1341848049.862754.png
1341848049.930835 rgb/1341848049.930835.png 1341848049.930867 depth/1341848049.930867.png
1341848049.963022 rgb/1341848049.963022.png 1341848049.963083 depth/1341848049.963083.png
1341848049.998757 rgb/1341848049.998757.png 1341848049.998810 depth/1341848049.998810.png
1341848050.030786 rgb/1341848050.030786.png 1341848050.030833 depth/1341848050.030833.png
1341848050.062661 rgb/1341848050.062661.png 1341848050.062676 depth/1341848050.062676.png
1341848050.098678 rgb/1341848050.098678.png 1341848050.098702 depth/1341848050.098702.png
1341848050.130710 rgb/1341848050.130710.png 1341848050.130726 depth/1341848050.130726.png
1341848050.166738 rgb/1341848050.166738.png 1341848050.167181 depth/1341848050.167181.png
1341848050.198726 rgb/1341848050.198726.png 1341848050.198752 depth/1341848050.198752.png
1341848050.230806 rgb/1341848050.230806.png 1341848050.230862 depth/1341848050.230862.png
1341848050.266732 rgb/1341848050.266732.png 1341848050.266756 depth/1341848050.266756.png
1341848050.298842 rgb/1341848050.298842.png 1341848050.298860 depth/1341848050.298860.png
1341848050.330688 rgb/1341848050.330688.png 1341848050.330736 depth/1341848050.330736.png
1341848050.366746 rgb/1341848050.366746.png 1341848050.366800 depth/1341848050.366800.png
1341848050.398693 rgb/1341848050.398693.png 1341848050.398776 depth/1341848050.398776.png
1341848050.434780 rgb/1341848050.434780.png 1341848050.434797 depth/1341848050.434797.png
1341848050.466655 rgb/1341848050.466655.png 1341848050.466671 depth/1341848050.466671.png
1341848050.498791 rgb/1341848050.498791.png 1341848050.499214 depth/1341848050.499214.png
1341848050.534849 rgb/1341848050.534849.png 1341848050.534897 depth/1341848050.534897.png
1341848050.566840 rgb/1341848050.566840.png 1341848050.566851 depth/1341848050.566851.png
1341848050.598790 rgb/1341848050.598790.png 1341848050.598800 depth/1341848050.598800.png
1341848050.634752 rgb/1341848050.634752.png 1341848050.634764 depth/1341848050.634764.png
1341848050.666816 rgb/1341848050.666816.png 1341848050.666834 depth/1341848050.666834.png
1341848050.702846 rgb/1341848050.702846.png 1341848050.702859 depth/1341848050.702859.png
1341848050.734789 rgb/1341848050.734789.png 1341848050.734804 depth/1341848050.734804.png
1341848050.766882 rgb/1341848050.766882.png 1341848050.766912 depth/1341848050.766912.png
1341848050.802875 rgb/1341848050.802875.png 1341848050.802891 depth/1341848050.802891.png
1341848050.834769 rgb/1341848050.834769.png 1341848050.834812 depth/1341848050.834812.png
1341848050.870719 rgb/1341848050.870719.png 1341848050.870939 depth/1341848050.870939.png
1341848050.902725 rgb/1341848050.902725.png 1341848050.902807 depth/1341848050.902807.png
1341848050.934794 rgb/1341848050.934794.png 1341848050.934824 depth/1341848050.934824.png
1341848050.970852 rgb/1341848050.970852.png 1341848050.970880 depth/1341848050.970880.png
1341848051.002763 rgb/1341848051.002763.png 1341848051.002816 depth/1341848051.002816.png
1341848051.035007 rgb/1341848051.035007.png 1341848051.035029 depth/1341848051.035029.png
1341848051.070784 rgb/1341848051.070784.png 1341848051.070827 depth/1341848051.070827.png
1341848051.102734 rgb/1341848051.102734.png 1341848051.102758 depth/1341848051.102758.png
1341848051.138713 rgb/1341848051.138713.png 1341848051.138744 depth/1341848051.138744.png
1341848051.170672 rgb/1341848051.170672.png 1341848051.170688 depth/1341848051.170688.png
1341848051.238747 rgb/1341848051.238747.png 1341848051.238791 depth/1341848051.238791.png
1341848051.270842 rgb/1341848051.270842.png 1341848051.270880 depth/1341848051.270880.png
1341848051.302718 rgb/1341848051.302718.png 1341848051.302805 depth/1341848051.302805.png
1341848051.338668 rgb/1341848051.338668.png 1341848051.338751 depth/1341848051.338751.png
1341848051.370895 rgb/1341848051.370895.png 1341848051.370907 depth/1341848051.370907.png
1341848051.406688 rgb/1341848051.406688.png 1341848051.406741 depth/1341848051.406741.png
1341848051.440006 rgb/1341848051.440006.png 1341848051.440034 depth/1341848051.440034.png
1341848051.470890 rgb/1341848051.470890.png 1341848051.470921 depth/1341848051.470921.png
1341848051.506718 rgb/1341848051.506718.png 1341848051.506733 depth/1341848051.506733.png
1341848051.538932 rgb/1341848051.538932.png 1341848051.538947 depth/1341848051.538947.png
1341848051.570738 rgb/1341848051.570738.png 1341848051.570784 depth/1341848051.570784.png
1341848051.606760 rgb/1341848051.606760.png 1341848051.606826 depth/1341848051.606826.png
1341848051.638863 rgb/1341848051.638863.png 1341848051.638893 depth/1341848051.638893.png
1341848051.674718 rgb/1341848051.674718.png 1341848051.674731 depth/1341848051.674731.png
1341848051.706714 rgb/1341848051.706714.png 1341848051.706731 depth/1341848051.706731.png
1341848051.738793 rgb/1341848051.738793.png 1341848051.738822 depth/1341848051.738822.png
1341848051.774823 rgb/1341848051.774823.png 1341848051.774838 depth/1341848051.774838.png
1341848051.806694 rgb/1341848051.806694.png 1341848051.806721 depth/1341848051.806721.png
1341848051.838757 rgb/1341848051.838757.png 1341848051.838774 depth/1341848051.838774.png
1341848051.874951 rgb/1341848051.874951.png 1341848051.875000 depth/1341848051.875000.png
1341848051.906707 rgb/1341848051.906707.png 1341848051.907209 depth/1341848051.907209.png
1341848051.942680 rgb/1341848051.942680.png 1341848051.942718 depth/1341848051.942718.png
1341848051.974762 rgb/1341848051.974762.png 1341848051.974829 depth/1341848051.974829.png
1341848052.006755 rgb/1341848052.006755.png 1341848052.006768 depth/1341848052.006768.png
1341848052.042751 rgb/1341848052.042751.png 1341848052.042793 depth/1341848052.042793.png
1341848052.074871 rgb/1341848052.074871.png 1341848052.074895 depth/1341848052.074895.png
1341848052.143014 rgb/1341848052.143014.png 1341848052.143046 depth/1341848052.143046.png
1341848052.178064 rgb/1341848052.178064.png 1341848052.179162 depth/1341848052.179162.png
1341848052.211397 rgb/1341848052.211397.png 1341848052.211672 depth/1341848052.211672.png
1341848052.242872 rgb/1341848052.242872.png 1341848052.243754 depth/1341848052.243754.png
1341848052.311125 rgb/1341848052.311125.png 1341848052.312593 depth/1341848052.312593.png
1341848052.342876 rgb/1341848052.342876.png 1341848052.342908 depth/1341848052.342908.png
1341848052.379476 rgb/1341848052.379476.png 1341848052.379633 depth/1341848052.379633.png
1341848052.412309 rgb/1341848052.412309.png 1341848052.413797 depth/1341848052.413797.png
1341848052.444722 rgb/1341848052.444722.png 1341848052.446183 depth/1341848052.446183.png
1341848052.481496 rgb/1341848052.481496.png 1341848052.481647 depth/1341848052.481647.png
1341848052.543277 rgb/1341848052.543277.png 1341848052.544440 depth/1341848052.544440.png
1341848052.579155 rgb/1341848052.579155.png 1341848052.579179 depth/1341848052.579179.png
1341848052.617750 rgb/1341848052.617750.png 1341848052.617779 depth/1341848052.617779.png
1341848052.678720 rgb/1341848052.678720.png 1341848052.678766 depth/1341848052.678766.png
1341848052.710822 rgb/1341848052.710822.png 1341848052.711174 depth/1341848052.711174.png
1341848052.746833 rgb/1341848052.746833.png 1341848052.746908 depth/1341848052.746908.png
1341848052.778710 rgb/1341848052.778710.png 1341848052.778723 depth/1341848052.778723.png
1341848052.810890 rgb/1341848052.810890.png 1341848052.810907 depth/1341848052.810907.png
1341848052.846856 rgb/1341848052.846856.png 1341848052.846871 depth/1341848052.846871.png
1341848052.878813 rgb/1341848052.878813.png 1341848052.878844 depth/1341848052.878844.png
1341848052.914694 rgb/1341848052.914694.png 1341848052.914725 depth/1341848052.914725.png
1341848052.946675 rgb/1341848052.946675.png 1341848052.946716 depth/1341848052.946716.png
1341848052.978684 rgb/1341848052.978684.png 1341848052.978840 depth/1341848052.978840.png
1341848053.014784 rgb/1341848053.014784.png 1341848053.014807 depth/1341848053.014807.png
1341848053.046693 rgb/1341848053.046693.png 1341848053.046724 depth/1341848053.046724.png
1341848053.082651 rgb/1341848053.082651.png 1341848053.082679 depth/1341848053.082679.png
1341848053.114846 rgb/1341848053.114846.png 1341848053.114860 depth/1341848053.114860.png
1341848053.146985 rgb/1341848053.146985.png 1341848053.148476 depth/1341848053.148476.png
1341848053.183210 rgb/1341848053.183210.png 1341848053.184337 depth/1341848053.184337.png
1341848053.214816 rgb/1341848053.214816.png 1341848053.214830 depth/1341848053.214830.png
1341848053.247961 rgb/1341848053.247961.png 1341848053.247980 depth/1341848053.247980.png
1341848053.289822 rgb/1341848053.289822.png 1341848053.292717 depth/1341848053.292717.png
1341848053.321709 rgb/1341848053.321709.png 1341848053.321732 depth/1341848053.321732.png
1341848053.353831 rgb/1341848053.353831.png 1341848053.356259 depth/1341848053.356259.png
1341848053.386096 rgb/1341848053.386096.png 1341848053.386732 depth/1341848053.386732.png
1341848053.421775 rgb/1341848053.421775.png 1341848053.421802 depth/1341848053.421802.png
1341848053.453749 rgb/1341848053.453749.png 1341848053.453759 depth/1341848053.453759.png
1341848053.485736 rgb/1341848053.485736.png 1341848053.485752 depth/1341848053.485752.png
1341848053.521747 rgb/1341848053.521747.png 1341848053.521768 depth/1341848053.521768.png
1341848053.553915 rgb/1341848053.553915.png 1341848053.553936 depth/1341848053.553936.png
1341848053.589737 rgb/1341848053.589737.png 1341848053.589767 depth/1341848053.589767.png
1341848053.621911 rgb/1341848053.621911.png 1341848053.621933 depth/1341848053.621933.png
1341848053.653792 rgb/1341848053.653792.png 1341848053.653842 depth/1341848053.653842.png
1341848053.689724 rgb/1341848053.689724.png 1341848053.689746 depth/1341848053.689746.png
1341848053.721697 rgb/1341848053.721697.png 1341848053.721712 depth/1341848053.721712.png
1341848053.758007 rgb/1341848053.758007.png 1341848053.758077 depth/1341848053.758077.png
1341848053.789882 rgb/1341848053.789882.png 1341848053.789892 depth/1341848053.789892.png
1341848053.821625 rgb/1341848053.821625.png 1341848053.821676 depth/1341848053.821676.png
1341848053.857784 rgb/1341848053.857784.png 1341848053.857801 depth/1341848053.857801.png
1341848053.889790 rgb/1341848053.889790.png 1341848053.889811 depth/1341848053.889811.png
1341848053.951067 rgb/1341848053.951067.png 1341848053.951082 depth/1341848053.951082.png
1341848053.986823 rgb/1341848053.986823.png 1341848053.986846 depth/1341848053.986846.png
1341848054.051032 rgb/1341848054.051032.png 1341848054.051048 depth/1341848054.051048.png
1341848054.086777 rgb/1341848054.086777.png 1341848054.086792 depth/1341848054.086792.png
1341848054.118853 rgb/1341848054.118853.png 1341848054.118865 depth/1341848054.118865.png
1341848054.155032 rgb/1341848054.155032.png 1341848054.155064 depth/1341848054.155064.png
1341848054.186687 rgb/1341848054.186687.png 1341848054.186722 depth/1341848054.186722.png
1341848054.219030 rgb/1341848054.219030.png 1341848054.219042 depth/1341848054.219042.png
1341848054.254827 rgb/1341848054.254827.png 1341848054.254842 depth/1341848054.254842.png
1341848054.286801 rgb/1341848054.286801.png 1341848054.286818 depth/1341848054.286818.png
1341848054.322895 rgb/1341848054.322895.png 1341848054.323319 depth/1341848054.323319.png
1341848054.354790 rgb/1341848054.354790.png 1341848054.354803 depth/1341848054.354803.png
1341848054.387103 rgb/1341848054.387103.png 1341848054.387855 depth/1341848054.387855.png
1341848054.422878 rgb/1341848054.422878.png 1341848054.423322 depth/1341848054.423322.png
1341848054.454739 rgb/1341848054.454739.png 1341848054.454751 depth/1341848054.454751.png
1341848054.486883 rgb/1341848054.486883.png 1341848054.486948 depth/1341848054.486948.png
1341848054.522689 rgb/1341848054.522689.png 1341848054.522735 depth/1341848054.522735.png
1341848054.554861 rgb/1341848054.554861.png 1341848054.554880 depth/1341848054.554880.png
1341848054.590790 rgb/1341848054.590790.png 1341848054.590808 depth/1341848054.590808.png
1341848054.622694 rgb/1341848054.622694.png 1341848054.622722 depth/1341848054.622722.png
1341848054.656449 rgb/1341848054.656449.png 1341848054.656477 depth/1341848054.656477.png
1341848054.691021 rgb/1341848054.691021.png 1341848054.691042 depth/1341848054.691042.png
1341848054.722739 rgb/1341848054.722739.png 1341848054.723258 depth/1341848054.723258.png
1341848054.754741 rgb/1341848054.754741.png 1341848054.755241 depth/1341848054.755241.png
1341848054.790887 rgb/1341848054.790887.png 1341848054.791409 depth/1341848054.791409.png
1341848054.822877 rgb/1341848054.822877.png 1341848054.823565 depth/1341848054.823565.png
1341848054.858903 rgb/1341848054.858903.png 1341848054.859037 depth/1341848054.859037.png
1341848054.890895 rgb/1341848054.890895.png 1341848054.890944 depth/1341848054.890944.png
1341848054.922754 rgb/1341848054.922754.png 1341848054.923230 depth/1341848054.923230.png
1341848054.958727 rgb/1341848054.958727.png 1341848054.958755 depth/1341848054.958755.png
1341848054.991052 rgb/1341848054.991052.png 1341848054.991085 depth/1341848054.991085.png
1341848055.023048 rgb/1341848055.023048.png 1341848055.023079 depth/1341848055.023079.png
1341848055.058739 rgb/1341848055.058739.png 1341848055.058760 depth/1341848055.058760.png
1341848055.090735 rgb/1341848055.090735.png 1341848055.090811 depth/1341848055.090811.png
1341848055.126977 rgb/1341848055.126977.png 1341848055.127018 depth/1341848055.127018.png
1341848055.159212 rgb/1341848055.159212.png 1341848055.159232 depth/1341848055.159232.png
1341848055.190986 rgb/1341848055.190986.png 1341848055.191010 depth/1341848055.191010.png
1341848055.226768 rgb/1341848055.226768.png 1341848055.226790 depth/1341848055.226790.png
1341848055.258881 rgb/1341848055.258881.png 1341848055.259331 depth/1341848055.259331.png
1341848055.294725 rgb/1341848055.294725.png 1341848055.294747 depth/1341848055.294747.png
1341848055.326795 rgb/1341848055.326795.png 1341848055.326811 depth/1341848055.326811.png
1341848055.358938 rgb/1341848055.358938.png 1341848055.359026 depth/1341848055.359026.png
1341848055.394711 rgb/1341848055.394711.png 1341848055.394755 depth/1341848055.394755.png
1341848055.426823 rgb/1341848055.426823.png 1341848055.426846 depth/1341848055.426846.png
1341848055.458813 rgb/1341848055.458813.png 1341848055.458862 depth/1341848055.458862.png
1341848055.494734 rgb/1341848055.494734.png 1341848055.494780 depth/1341848055.494780.png
1341848055.526713 rgb/1341848055.526713.png 1341848055.526772 depth/1341848055.526772.png
1341848055.562613 rgb/1341848055.562613.png 1341848055.562659 depth/1341848055.562659.png
1341848055.594685 rgb/1341848055.594685.png 1341848055.594704 depth/1341848055.594704.png
1341848055.626675 rgb/1341848055.626675.png 1341848055.626690 depth/1341848055.626690.png
1341848055.662951 rgb/1341848055.662951.png 1341848055.662971 depth/1341848055.662971.png
1341848055.694797 rgb/1341848055.694797.png 1341848055.694815 depth/1341848055.694815.png
1341848055.726774 rgb/1341848055.726774.png 1341848055.726799 depth/1341848055.726799.png
1341848055.762799 rgb/1341848055.762799.png 1341848055.762858 depth/1341848055.762858.png
1341848055.794951 rgb/1341848055.794951.png 1341848055.795020 depth/1341848055.795020.png
1341848055.830810 rgb/1341848055.830810.png 1341848055.830827 depth/1341848055.830827.png
1341848055.862804 rgb/1341848055.862804.png 1341848055.862847 depth/1341848055.862847.png
1341848055.894792 rgb/1341848055.894792.png 1341848055.894806 depth/1341848055.894806.png
1341848055.930676 rgb/1341848055.930676.png 1341848055.930688 depth/1341848055.930688.png
1341848055.962765 rgb/1341848055.962765.png 1341848055.962807 depth/1341848055.962807.png
1341848055.994709 rgb/1341848055.994709.png 1341848055.994743 depth/1341848055.994743.png
1341848056.030693 rgb/1341848056.030693.png 1341848056.030743 depth/1341848056.030743.png
1341848056.062776 rgb/1341848056.062776.png 1341848056.062796 depth/1341848056.062796.png
1341848056.098792 rgb/1341848056.098792.png 1341848056.098811 depth/1341848056.098811.png
1341848056.130649 rgb/1341848056.130649.png 1341848056.130661 depth/1341848056.130661.png
1341848056.162731 rgb/1341848056.162731.png 1341848056.162741 depth/1341848056.162741.png
1341848056.198744 rgb/1341848056.198744.png 1341848056.198760 depth/1341848056.198760.png
1341848056.230727 rgb/1341848056.230727.png 1341848056.230784 depth/1341848056.230784.png
1341848056.263915 rgb/1341848056.263915.png 1341848056.263942 depth/1341848056.263942.png
1341848056.298771 rgb/1341848056.298771.png 1341848056.298811 depth/1341848056.298811.png
1341848056.330676 rgb/1341848056.330676.png 1341848056.330687 depth/1341848056.330687.png
1341848056.366737 rgb/1341848056.366737.png 1341848056.366752 depth/1341848056.366752.png
1341848056.398744 rgb/1341848056.398744.png 1341848056.399274 depth/1341848056.399274.png
1341848056.430750 rgb/1341848056.430750.png 1341848056.430803 depth/1341848056.430803.png
1341848056.466830 rgb/1341848056.466830.png 1341848056.466874 depth/1341848056.466874.png
1341848056.498895 rgb/1341848056.498895.png 1341848056.498914 depth/1341848056.498914.png
1341848056.534778 rgb/1341848056.534778.png 1341848056.534856 depth/1341848056.534856.png
1341848056.566729 rgb/1341848056.566729.png 1341848056.566742 depth/1341848056.566742.png
1341848056.598948 rgb/1341848056.598948.png 1341848056.599048 depth/1341848056.599048.png
1341848056.634801 rgb/1341848056.634801.png 1341848056.635005 depth/1341848056.635005.png
1341848056.666759 rgb/1341848056.666759.png 1341848056.666800 depth/1341848056.666800.png
1341848056.698889 rgb/1341848056.698889.png 1341848056.698898 depth/1341848056.698898.png
1341848056.734784 rgb/1341848056.734784.png 1341848056.735297 depth/1341848056.735297.png
1341848056.766724 rgb/1341848056.766724.png 1341848056.766792 depth/1341848056.766792.png
1341848056.802861 rgb/1341848056.802861.png 1341848056.802899 depth/1341848056.802899.png
1341848056.834980 rgb/1341848056.834980.png 1341848056.835035 depth/1341848056.835035.png
1341848056.866661 rgb/1341848056.866661.png 1341848056.866671 depth/1341848056.866671.png
1341848056.902748 rgb/1341848056.902748.png 1341848056.902779 depth/1341848056.902779.png
1341848056.934715 rgb/1341848056.934715.png 1341848056.934953 depth/1341848056.934953.png
1341848056.966788 rgb/1341848056.966788.png 1341848056.966823 depth/1341848056.966823.png
1341848057.002703 rgb/1341848057.002703.png 1341848057.002763 depth/1341848057.002763.png
1341848057.034763 rgb/1341848057.034763.png 1341848057.035020 depth/1341848057.035020.png
1341848057.070964 rgb/1341848057.070964.png 1341848057.070988 depth/1341848057.070988.png
1341848057.102757 rgb/1341848057.102757.png 1341848057.102797 depth/1341848057.102797.png
1341848057.134714 rgb/1341848057.134714.png 1341848057.134974 depth/1341848057.134974.png
1341848057.170739 rgb/1341848057.170739.png 1341848057.170751 depth/1341848057.170751.png
1341848057.202641 rgb/1341848057.202641.png 1341848057.202667 depth/1341848057.202667.png
1341848057.234679 rgb/1341848057.234679.png 1341848057.234693 depth/1341848057.234693.png
1341848057.270814 rgb/1341848057.270814.png 1341848057.270823 depth/1341848057.270823.png
1341848057.302860 rgb/1341848057.302860.png 1341848057.302980 depth/1341848057.302980.png
1341848057.338756 rgb/1341848057.338756.png 1341848057.338780 depth/1341848057.338780.png
1341848057.370841 rgb/1341848057.370841.png 1341848057.370867 depth/1341848057.370867.png
1341848057.402722 rgb/1341848057.402722.png 1341848057.402756 depth/1341848057.402756.png
1341848057.438870 rgb/1341848057.438870.png 1341848057.438880 depth/1341848057.438880.png
1341848057.470699 rgb/1341848057.470699.png 1341848057.470718 depth/1341848057.470718.png
1341848057.506720 rgb/1341848057.506720.png 1341848057.506753 depth/1341848057.506753.png
1341848057.538788 rgb/1341848057.538788.png 1341848057.538804 depth/1341848057.538804.png
1341848057.571069 rgb/1341848057.571069.png 1341848057.571100 depth/1341848057.571100.png
1341848057.606668 rgb/1341848057.606668.png 1341848057.606677 depth/1341848057.606677.png
1341848057.638819 rgb/1341848057.638819.png 1341848057.638855 depth/1341848057.638855.png
1341848057.670943 rgb/1341848057.670943.png 1341848057.671015 depth/1341848057.671015.png
1341848057.706823 rgb/1341848057.706823.png 1341848057.706841 depth/1341848057.706841.png
1341848057.738890 rgb/1341848057.738890.png 1341848057.739645 depth/1341848057.739645.png
1341848057.774986 rgb/1341848057.774986.png 1341848057.775609 depth/1341848057.775609.png
1341848057.806842 rgb/1341848057.806842.png 1341848057.806912 depth/1341848057.806912.png
1341848057.838760 rgb/1341848057.838760.png 1341848057.838766 depth/1341848057.838766.png
1341848057.874817 rgb/1341848057.874817.png 1341848057.874847 depth/1341848057.874847.png
1341848057.906831 rgb/1341848057.906831.png 1341848057.906846 depth/1341848057.906846.png
1341848057.938847 rgb/1341848057.938847.png 1341848057.938888 depth/1341848057.938888.png
1341848057.975316 rgb/1341848057.975316.png 1341848057.975330 depth/1341848057.975330.png
1341848058.006833 rgb/1341848058.006833.png 1341848058.006850 depth/1341848058.006850.png
1341848058.042753 rgb/1341848058.042753.png 1341848058.042790 depth/1341848058.042790.png
1341848058.075970 rgb/1341848058.075970.png 1341848058.075985 depth/1341848058.075985.png
1341848058.106790 rgb/1341848058.106790.png 1341848058.106860 depth/1341848058.106860.png
1341848058.142699 rgb/1341848058.142699.png 1341848058.142719 depth/1341848058.142719.png
1341848058.174743 rgb/1341848058.174743.png 1341848058.174770 depth/1341848058.174770.png
1341848058.207081 rgb/1341848058.207081.png 1341848058.207102 depth/1341848058.207102.png
1341848058.242740 rgb/1341848058.242740.png 1341848058.242749 depth/1341848058.242749.png
1341848058.274694 rgb/1341848058.274694.png 1341848058.274839 depth/1341848058.274839.png
1341848058.310701 rgb/1341848058.310701.png 1341848058.310722 depth/1341848058.310722.png
1341848058.343169 rgb/1341848058.343169.png 1341848058.343218 depth/1341848058.343218.png
1341848058.374887 rgb/1341848058.374887.png 1341848058.374917 depth/1341848058.374917.png
1341848058.410669 rgb/1341848058.410669.png 1341848058.410676 depth/1341848058.410676.png
1341848058.442794 rgb/1341848058.442794.png 1341848058.442828 depth/1341848058.442828.png
1341848058.474732 rgb/1341848058.474732.png 1341848058.474753 depth/1341848058.474753.png
1341848058.542970 rgb/1341848058.542970.png 1341848058.542987 depth/1341848058.542987.png
1341848058.578948 rgb/1341848058.578948.png 1341848058.578964 depth/1341848058.578964.png
1341848058.610842 rgb/1341848058.610842.png 1341848058.610871 depth/1341848058.610871.png
1341848058.643060 rgb/1341848058.643060.png 1341848058.643076 depth/1341848058.643076.png
1341848058.678730 rgb/1341848058.678730.png 1341848058.678770 depth/1341848058.678770.png
1341848058.710728 rgb/1341848058.710728.png 1341848058.710766 depth/1341848058.710766.png
1341848058.746819 rgb/1341848058.746819.png 1341848058.746854 depth/1341848058.746854.png
1341848058.778710 rgb/1341848058.778710.png 1341848058.778785 depth/1341848058.778785.png
1341848058.810874 rgb/1341848058.810874.png 1341848058.811237 depth/1341848058.811237.png
1341848058.846829 rgb/1341848058.846829.png 1341848058.846867 depth/1341848058.846867.png
1341848058.879577 rgb/1341848058.879577.png 1341848058.880257 depth/1341848058.880257.png
1341848058.946807 rgb/1341848058.946807.png 1341848058.946831 depth/1341848058.946831.png
1341848058.978865 rgb/1341848058.978865.png 1341848058.978887 depth/1341848058.978887.png
1341848059.014660 rgb/1341848059.014660.png 1341848059.014688 depth/1341848059.014688.png
1341848059.046707 rgb/1341848059.046707.png 1341848059.046732 depth/1341848059.046732.png
1341848059.078771 rgb/1341848059.078771.png 1341848059.078837 depth/1341848059.078837.png
1341848059.114675 rgb/1341848059.114675.png 1341848059.114705 depth/1341848059.114705.png
1341848059.146706 rgb/1341848059.146706.png 1341848059.146722 depth/1341848059.146722.png
1341848059.178722 rgb/1341848059.178722.png 1341848059.178787 depth/1341848059.178787.png
1341848059.214738 rgb/1341848059.214738.png 1341848059.214758 depth/1341848059.214758.png
1341848059.246762 rgb/1341848059.246762.png 1341848059.246787 depth/1341848059.246787.png
1341848059.282693 rgb/1341848059.282693.png 1341848059.282764 depth/1341848059.282764.png
1341848059.314667 rgb/1341848059.314667.png 1341848059.314695 depth/1341848059.314695.png
1341848059.346758 rgb/1341848059.346758.png 1341848059.346817 depth/1341848059.346817.png
1341848059.382694 rgb/1341848059.382694.png 1341848059.382710 depth/1341848059.382710.png
1341848059.414736 rgb/1341848059.414736.png 1341848059.414763 depth/1341848059.414763.png
1341848059.446788 rgb/1341848059.446788.png 1341848059.446880 depth/1341848059.446880.png
1341848059.482693 rgb/1341848059.482693.png 1341848059.482709 depth/1341848059.482709.png
1341848059.514652 rgb/1341848059.514652.png 1341848059.514665 depth/1341848059.514665.png
1341848059.550754 rgb/1341848059.550754.png 1341848059.550789 depth/1341848059.550789.png
1341848059.582695 rgb/1341848059.582695.png 1341848059.582712 depth/1341848059.582712.png
1341848059.614734 rgb/1341848059.614734.png 1341848059.614760 depth/1341848059.614760.png
1341848059.650722 rgb/1341848059.650722.png 1341848059.650736 depth/1341848059.650736.png
1341848059.682731 rgb/1341848059.682731.png 1341848059.682765 depth/1341848059.682765.png
1341848059.718703 rgb/1341848059.718703.png 1341848059.718727 depth/1341848059.718727.png
1341848059.750904 rgb/1341848059.750904.png 1341848059.750937 depth/1341848059.750937.png
1341848059.782774 rgb/1341848059.782774.png 1341848059.782784 depth/1341848059.782784.png
1341848059.818759 rgb/1341848059.818759.png 1341848059.818786 depth/1341848059.818786.png
1341848059.850685 rgb/1341848059.850685.png 1341848059.850742 depth/1341848059.850742.png
1341848059.882730 rgb/1341848059.882730.png 1341848059.882739 depth/1341848059.882739.png
1341848059.918755 rgb/1341848059.918755.png 1341848059.918781 depth/1341848059.918781.png
1341848059.950805 rgb/1341848059.950805.png 1341848059.951468 depth/1341848059.951468.png
1341848059.986776 rgb/1341848059.986776.png 1341848059.986870 depth/1341848059.986870.png
1341848060.018660 rgb/1341848060.018660.png 1341848060.018699 depth/1341848060.018699.png
1341848060.050701 rgb/1341848060.050701.png 1341848060.050726 depth/1341848060.050726.png
1341848060.086783 rgb/1341848060.086783.png 1341848060.086804 depth/1341848060.086804.png
1341848060.118813 rgb/1341848060.118813.png 1341848060.118826 depth/1341848060.118826.png
1341848060.150800 rgb/1341848060.150800.png 1341848060.152187 depth/1341848060.152187.png
1341848060.186872 rgb/1341848060.186872.png 1341848060.186902 depth/1341848060.186902.png
1341848060.218851 rgb/1341848060.218851.png 1341848060.218926 depth/1341848060.218926.png
1341848060.254799 rgb/1341848060.254799.png 1341848060.255357 depth/1341848060.255357.png
1341848060.287466 rgb/1341848060.287466.png 1341848060.287482 depth/1341848060.287482.png
1341848060.318914 rgb/1341848060.318914.png 1341848060.318945 depth/1341848060.318945.png
1341848060.354641 rgb/1341848060.354641.png 1341848060.354688 depth/1341848060.354688.png
1341848060.387254 rgb/1341848060.387254.png 1341848060.387291 depth/1341848060.387291.png
1341848060.418639 rgb/1341848060.418639.png 1341848060.418684 depth/1341848060.418684.png
1341848060.454775 rgb/1341848060.454775.png 1341848060.454794 depth/1341848060.454794.png
1341848060.486697 rgb/1341848060.486697.png 1341848060.486771 depth/1341848060.486771.png
1341848060.522925 rgb/1341848060.522925.png 1341848060.523008 depth/1341848060.523008.png
1341848060.554710 rgb/1341848060.554710.png 1341848060.554724 depth/1341848060.554724.png
1341848060.586692 rgb/1341848060.586692.png 1341848060.586706 depth/1341848060.586706.png
1341848060.622697 rgb/1341848060.622697.png 1341848060.622721 depth/1341848060.622721.png
1341848060.656087 rgb/1341848060.656087.png 1341848060.656113 depth/1341848060.656113.png
1341848060.687258 rgb/1341848060.687258.png 1341848060.687324 depth/1341848060.687324.png
1341848060.723165 rgb/1341848060.723165.png 1341848060.724561 depth/1341848060.724561.png
1341848060.757863 rgb/1341848060.757863.png 1341848060.757889 depth/1341848060.757889.png
1341848060.790920 rgb/1341848060.790920.png 1341848060.791034 depth/1341848060.791034.png
1341848060.823967 rgb/1341848060.823967.png 1341848060.829094 depth/1341848060.829094.png
1341848060.862432 rgb/1341848060.862432.png 1341848060.863663 depth/1341848060.863663.png
1341848060.923126 rgb/1341848060.923126.png 1341848060.926419 depth/1341848060.926419.png
1341848060.960845 rgb/1341848060.960845.png 1341848060.961890 depth/1341848060.961890.png
1341848060.996857 rgb/1341848060.996857.png 1341848060.997593 depth/1341848060.997593.png
1341848061.030587 rgb/1341848061.030587.png 1341848061.031332 depth/1341848061.031332.png
1341848061.062246 rgb/1341848061.062246.png 1341848061.062516 depth/1341848061.062516.png
1341848061.100583 rgb/1341848061.100583.png 1341848061.101130 depth/1341848061.101130.png
1341848061.129837 rgb/1341848061.129837.png 1341848061.129853 depth/1341848061.129853.png
1341848061.197947 rgb/1341848061.197947.png 1341848061.197987 depth/1341848061.197987.png
1341848061.259408 rgb/1341848061.259408.png 1341848061.259586 depth/1341848061.259586.png
1341848061.290885 rgb/1341848061.290885.png 1341848061.290998 depth/1341848061.290998.png
1341848061.326612 rgb/1341848061.326612.png 1341848061.326647 depth/1341848061.326647.png
1341848061.358867 rgb/1341848061.358867.png 1341848061.358908 depth/1341848061.358908.png
1341848061.390845 rgb/1341848061.390845.png 1341848061.391495 depth/1341848061.391495.png
1341848061.426913 rgb/1341848061.426913.png 1341848061.426942 depth/1341848061.426942.png
1341848061.458837 rgb/1341848061.458837.png 1341848061.458854 depth/1341848061.458854.png
1341848061.494657 rgb/1341848061.494657.png 1341848061.495433 depth/1341848061.495433.png
1341848061.526736 rgb/1341848061.526736.png 1341848061.526886 depth/1341848061.526886.png
1341848061.558821 rgb/1341848061.558821.png 1341848061.558836 depth/1341848061.558836.png
1341848061.594750 rgb/1341848061.594750.png 1341848061.594776 depth/1341848061.594776.png
1341848061.626731 rgb/1341848061.626731.png 1341848061.626753 depth/1341848061.626753.png
1341848061.658831 rgb/1341848061.658831.png 1341848061.658845 depth/1341848061.658845.png
1341848061.694894 rgb/1341848061.694894.png 1341848061.694932 depth/1341848061.694932.png
1341848061.726726 rgb/1341848061.726726.png 1341848061.726750 depth/1341848061.726750.png
1341848061.762815 rgb/1341848061.762815.png 1341848061.762840 depth/1341848061.762840.png
1341848061.794816 rgb/1341848061.794816.png 1341848061.795285 depth/1341848061.795285.png
1341848061.826740 rgb/1341848061.826740.png 1341848061.826754 depth/1341848061.826754.png
1341848061.862883 rgb/1341848061.862883.png 1341848061.862902 depth/1341848061.862902.png
1341848061.894834 rgb/1341848061.894834.png 1341848061.894887 depth/1341848061.894887.png
1341848061.930667 rgb/1341848061.930667.png 1341848061.930754 depth/1341848061.930754.png
1341848061.962828 rgb/1341848061.962828.png 1341848061.962857 depth/1341848061.962857.png
1341848061.997188 rgb/1341848061.997188.png 1341848061.997201 depth/1341848061.997201.png
1341848062.030704 rgb/1341848062.030704.png 1341848062.030723 depth/1341848062.030723.png
1341848062.063265 rgb/1341848062.063265.png 1341848062.064058 depth/1341848062.064058.png
1341848062.094872 rgb/1341848062.094872.png 1341848062.094893 depth/1341848062.094893.png
1341848062.130773 rgb/1341848062.130773.png 1341848062.130816 depth/1341848062.130816.png
1341848062.163385 rgb/1341848062.163385.png 1341848062.163399 depth/1341848062.163399.png
1341848062.198718 rgb/1341848062.198718.png 1341848062.198960 depth/1341848062.198960.png
1341848062.230750 rgb/1341848062.230750.png 1341848062.230763 depth/1341848062.230763.png
1341848062.262814 rgb/1341848062.262814.png 1341848062.262858 depth/1341848062.262858.png
1341848062.299276 rgb/1341848062.299276.png 1341848062.299285 depth/1341848062.299285.png
1341848062.330839 rgb/1341848062.330839.png 1341848062.330968 depth/1341848062.330968.png
1341848062.362763 rgb/1341848062.362763.png 1341848062.362798 depth/1341848062.362798.png
1341848062.398825 rgb/1341848062.398825.png 1341848062.398836 depth/1341848062.398836.png
1341848062.430832 rgb/1341848062.430832.png 1341848062.430844 depth/1341848062.430844.png
1341848062.466855 rgb/1341848062.466855.png 1341848062.466879 depth/1341848062.466879.png
1341848062.498723 rgb/1341848062.498723.png 1341848062.498743 depth/1341848062.498743.png
1341848062.530743 rgb/1341848062.530743.png 1341848062.530759 depth/1341848062.530759.png
1341848062.566929 rgb/1341848062.566929.png 1341848062.566959 depth/1341848062.566959.png
1341848062.598817 rgb/1341848062.598817.png 1341848062.598829 depth/1341848062.598829.png
1341848062.630793 rgb/1341848062.630793.png 1341848062.630824 depth/1341848062.630824.png
1341848062.666740 rgb/1341848062.666740.png 1341848062.666771 depth/1341848062.666771.png
1341848062.698720 rgb/1341848062.698720.png 1341848062.698743 depth/1341848062.698743.png
1341848062.734924 rgb/1341848062.734924.png 1341848062.734939 depth/1341848062.734939.png
1341848062.766819 rgb/1341848062.766819.png 1341848062.766877 depth/1341848062.766877.png
1341848062.798717 rgb/1341848062.798717.png 1341848062.798764 depth/1341848062.798764.png
1341848062.834828 rgb/1341848062.834828.png 1341848062.834849 depth/1341848062.834849.png
1341848062.866781 rgb/1341848062.866781.png 1341848062.867238 depth/1341848062.867238.png
1341848062.899075 rgb/1341848062.899075.png 1341848062.899092 depth/1341848062.899092.png
1341848062.934962 rgb/1341848062.934962.png 1341848062.934977 depth/1341848062.934977.png
1341848062.966930 rgb/1341848062.966930.png 1341848062.966957 depth/1341848062.966957.png
1341848063.002905 rgb/1341848063.002905.png 1341848063.002915 depth/1341848063.002915.png
1341848063.034972 rgb/1341848063.034972.png 1341848063.035491 depth/1341848063.035491.png
1341848063.066737 rgb/1341848063.066737.png 1341848063.066749 depth/1341848063.066749.png
1341848063.102822 rgb/1341848063.102822.png 1341848063.102832 depth/1341848063.102832.png
1341848063.135045 rgb/1341848063.135045.png 1341848063.135160 depth/1341848063.135160.png
1341848063.170739 rgb/1341848063.170739.png 1341848063.170794 depth/1341848063.170794.png
1341848063.202662 rgb/1341848063.202662.png 1341848063.202765 depth/1341848063.202765.png
1341848063.234990 rgb/1341848063.234990.png 1341848063.235006 depth/1341848063.235006.png
1341848063.270800 rgb/1341848063.270800.png 1341848063.270816 depth/1341848063.270816.png
1341848063.302788 rgb/1341848063.302788.png 1341848063.302814 depth/1341848063.302814.png
1341848063.334854 rgb/1341848063.334854.png 1341848063.335470 depth/1341848063.335470.png
1341848063.370653 rgb/1341848063.370653.png 1341848063.370688 depth/1341848063.370688.png
1341848063.402698 rgb/1341848063.402698.png 1341848063.402728 depth/1341848063.402728.png
1341848063.439276 rgb/1341848063.439276.png 1341848063.439294 depth/1341848063.439294.png
1341848063.470742 rgb/1341848063.470742.png 1341848063.470764 depth/1341848063.470764.png
1341848063.502776 rgb/1341848063.502776.png 1341848063.502801 depth/1341848063.502801.png
1341848063.541802 rgb/1341848063.541802.png 1341848063.541821 depth/1341848063.541821.png
1341848063.577805 rgb/1341848063.577805.png 1341848063.577827 depth/1341848063.577827.png
1341848063.609732 rgb/1341848063.609732.png 1341848063.609780 depth/1341848063.609780.png
1341848063.643039 rgb/1341848063.643039.png 1341848063.643057 depth/1341848063.643057.png
1341848063.677955 rgb/1341848063.677955.png 1341848063.677981 depth/1341848063.677981.png
1341848063.709890 rgb/1341848063.709890.png 1341848063.709915 depth/1341848063.709915.png
1341848063.745768 rgb/1341848063.745768.png 1341848063.745783 depth/1341848063.745783.png
1341848063.777773 rgb/1341848063.777773.png 1341848063.777929 depth/1341848063.777929.png
1341848063.809840 rgb/1341848063.809840.png 1341848063.809857 depth/1341848063.809857.png
1341848063.845733 rgb/1341848063.845733.png 1341848063.845775 depth/1341848063.845775.png
1341848063.877902 rgb/1341848063.877902.png 1341848063.877913 depth/1341848063.877913.png
1341848063.913769 rgb/1341848063.913769.png 1341848063.913781 depth/1341848063.913781.png
1341848063.945802 rgb/1341848063.945802.png 1341848063.946407 depth/1341848063.946407.png
1341848063.977856 rgb/1341848063.977856.png 1341848063.977868 depth/1341848063.977868.png
1341848064.013951 rgb/1341848064.013951.png 1341848064.013963 depth/1341848064.013963.png
1341848064.045815 rgb/1341848064.045815.png 1341848064.045830 depth/1341848064.045830.png
1341848064.081699 rgb/1341848064.081699.png 1341848064.081716 depth/1341848064.081716.png
1341848064.113685 rgb/1341848064.113685.png 1341848064.113699 depth/1341848064.113699.png
1341848064.145823 rgb/1341848064.145823.png 1341848064.145896 depth/1341848064.145896.png
1341848064.181846 rgb/1341848064.181846.png 1341848064.181871 depth/1341848064.181871.png
1341848064.213863 rgb/1341848064.213863.png 1341848064.213916 depth/1341848064.213916.png
1341848064.249771 rgb/1341848064.249771.png 1341848064.249803 depth/1341848064.249803.png
1341848064.282977 rgb/1341848064.282977.png 1341848064.283921 depth/1341848064.283921.png
1341848064.313795 rgb/1341848064.313795.png 1341848064.313821 depth/1341848064.313821.png
1341848064.349790 rgb/1341848064.349790.png 1341848064.349800 depth/1341848064.349800.png
1341848064.382619 rgb/1341848064.382619.png 1341848064.382881 depth/1341848064.382881.png
1341848064.418063 rgb/1341848064.418063.png 1341848064.418076 depth/1341848064.418076.png
1341848064.449767 rgb/1341848064.449767.png 1341848064.449781 depth/1341848064.449781.png
1341848064.481773 rgb/1341848064.481773.png 1341848064.481794 depth/1341848064.481794.png
1341848064.518010 rgb/1341848064.518010.png 1341848064.518639 depth/1341848064.518639.png
1341848064.549704 rgb/1341848064.549704.png 1341848064.549726 depth/1341848064.549726.png
1341848064.581714 rgb/1341848064.581714.png 1341848064.581772 depth/1341848064.581772.png
1341848064.617693 rgb/1341848064.617693.png 1341848064.617728 depth/1341848064.617728.png
1341848064.649724 rgb/1341848064.649724.png 1341848064.649739 depth/1341848064.649739.png
1341848064.685821 rgb/1341848064.685821.png 1341848064.685871 depth/1341848064.685871.png
1341848064.749892 rgb/1341848064.749892.png 1341848064.749986 depth/1341848064.749986.png
1341848064.810737 rgb/1341848064.810737.png 1341848064.810771 depth/1341848064.810771.png
1341848064.842702 rgb/1341848064.842702.png 1341848064.842765 depth/1341848064.842765.png
1341848064.878850 rgb/1341848064.878850.png 1341848064.878871 depth/1341848064.878871.png
1341848064.910832 rgb/1341848064.910832.png 1341848064.910861 depth/1341848064.910861.png
1341848064.946850 rgb/1341848064.946850.png 1341848064.946870 depth/1341848064.946870.png
1341848064.978809 rgb/1341848064.978809.png 1341848064.978833 depth/1341848064.978833.png
1341848065.010770 rgb/1341848065.010770.png 1341848065.010849 depth/1341848065.010849.png
1341848065.046751 rgb/1341848065.046751.png 1341848065.046796 depth/1341848065.046796.png
1341848065.078713 rgb/1341848065.078713.png 1341848065.078740 depth/1341848065.078740.png
1341848065.110686 rgb/1341848065.110686.png 1341848065.110913 depth/1341848065.110913.png
1341848065.146689 rgb/1341848065.146689.png 1341848065.146705 depth/1341848065.146705.png
1341848065.178847 rgb/1341848065.178847.png 1341848065.178872 depth/1341848065.178872.png
1341848065.214760 rgb/1341848065.214760.png 1341848065.214817 depth/1341848065.214817.png
1341848065.246768 rgb/1341848065.246768.png 1341848065.246815 depth/1341848065.246815.png
1341848065.278735 rgb/1341848065.278735.png 1341848065.278785 depth/1341848065.278785.png
1341848065.314761 rgb/1341848065.314761.png 1341848065.314782 depth/1341848065.314782.png
1341848065.346776 rgb/1341848065.346776.png 1341848065.346874 depth/1341848065.346874.png
1341848065.382824 rgb/1341848065.382824.png 1341848065.382883 depth/1341848065.382883.png
1341848065.414914 rgb/1341848065.414914.png 1341848065.414947 depth/1341848065.414947.png
1341848065.446728 rgb/1341848065.446728.png 1341848065.447032 depth/1341848065.447032.png
1341848065.482830 rgb/1341848065.482830.png 1341848065.483011 depth/1341848065.483011.png
1341848065.514745 rgb/1341848065.514745.png 1341848065.515200 depth/1341848065.515200.png
1341848065.546916 rgb/1341848065.546916.png 1341848065.546929 depth/1341848065.546929.png
1341848065.582742 rgb/1341848065.582742.png 1341848065.582781 depth/1341848065.582781.png
1341848065.614763 rgb/1341848065.614763.png 1341848065.615224 depth/1341848065.615224.png
1341848065.682873 rgb/1341848065.682873.png 1341848065.682923 depth/1341848065.682923.png
1341848065.714808 rgb/1341848065.714808.png 1341848065.714841 depth/1341848065.714841.png
1341848065.750674 rgb/1341848065.750674.png 1341848065.750692 depth/1341848065.750692.png
1341848065.782722 rgb/1341848065.782722.png 1341848065.782781 depth/1341848065.782781.png
1341848065.814742 rgb/1341848065.814742.png 1341848065.814773 depth/1341848065.814773.png
1341848065.850746 rgb/1341848065.850746.png 1341848065.850775 depth/1341848065.850775.png
1341848065.918698 rgb/1341848065.918698.png 1341848065.918742 depth/1341848065.918742.png
1341848065.950762 rgb/1341848065.950762.png 1341848065.950803 depth/1341848065.950803.png
1341848065.982774 rgb/1341848065.982774.png 1341848065.982829 depth/1341848065.982829.png
1341848066.018773 rgb/1341848066.018773.png 1341848066.018836 depth/1341848066.018836.png
1341848066.050717 rgb/1341848066.050717.png 1341848066.050784 depth/1341848066.050784.png
1341848066.082818 rgb/1341848066.082818.png 1341848066.082851 depth/1341848066.082851.png
1341848066.118721 rgb/1341848066.118721.png 1341848066.118762 depth/1341848066.118762.png
1341848066.150964 rgb/1341848066.150964.png 1341848066.151663 depth/1341848066.151663.png
1341848066.186782 rgb/1341848066.186782.png 1341848066.186806 depth/1341848066.186806.png
1341848066.218688 rgb/1341848066.218688.png 1341848066.218701 depth/1341848066.218701.png
1341848066.250777 rgb/1341848066.250777.png 1341848066.250794 depth/1341848066.250794.png
1341848066.286736 rgb/1341848066.286736.png 1341848066.286752 depth/1341848066.286752.png
1341848066.318695 rgb/1341848066.318695.png 1341848066.318714 depth/1341848066.318714.png
1341848066.354797 rgb/1341848066.354797.png 1341848066.354854 depth/1341848066.354854.png
1341848066.386761 rgb/1341848066.386761.png 1341848066.386795 depth/1341848066.386795.png
1341848066.418820 rgb/1341848066.418820.png 1341848066.418853 depth/1341848066.418853.png
1341848066.454695 rgb/1341848066.454695.png 1341848066.454708 depth/1341848066.454708.png
1341848066.486874 rgb/1341848066.486874.png 1341848066.486902 depth/1341848066.486902.png
1341848066.522806 rgb/1341848066.522806.png 1341848066.523149 depth/1341848066.523149.png
1341848066.555107 rgb/1341848066.555107.png 1341848066.560526 depth/1341848066.560526.png
1341848066.623500 rgb/1341848066.623500.png 1341848066.624153 depth/1341848066.624153.png
1341848066.655239 rgb/1341848066.655239.png 1341848066.655262 depth/1341848066.655262.png
1341848066.697724 rgb/1341848066.697724.png 1341848066.698980 depth/1341848066.698980.png
1341848066.732527 rgb/1341848066.732527.png 1341848066.733333 depth/1341848066.733333.png
1341848066.764415 rgb/1341848066.764415.png 1341848066.765329 depth/1341848066.765329.png
1341848066.795253 rgb/1341848066.795253.png 1341848066.795567 depth/1341848066.795567.png
1341848066.833355 rgb/1341848066.833355.png 1341848066.834424 depth/1341848066.834424.png
1341848066.862103 rgb/1341848066.862103.png 1341848066.862114 depth/1341848066.862114.png
1341848066.905023 rgb/1341848066.905023.png 1341848066.905636 depth/1341848066.905636.png
1341848066.930221 rgb/1341848066.930221.png 1341848066.930239 depth/1341848066.930239.png
1341848066.997936 rgb/1341848066.997936.png 1341848066.998757 depth/1341848066.998757.png
1341848067.054702 rgb/1341848067.054702.png 1341848067.054719 depth/1341848067.054719.png
1341848067.090940 rgb/1341848067.090940.png 1341848067.090960 depth/1341848067.090960.png
1341848067.122963 rgb/1341848067.122963.png 1341848067.122977 depth/1341848067.122977.png
1341848067.158821 rgb/1341848067.158821.png 1341848067.158843 depth/1341848067.158843.png
1341848067.191143 rgb/1341848067.191143.png 1341848067.191172 depth/1341848067.191172.png
1341848067.222948 rgb/1341848067.222948.png 1341848067.223798 depth/1341848067.223798.png
1341848067.258733 rgb/1341848067.258733.png 1341848067.258827 depth/1341848067.258827.png
1341848067.322816 rgb/1341848067.322816.png 1341848067.322831 depth/1341848067.322831.png
1341848067.358674 rgb/1341848067.358674.png 1341848067.358740 depth/1341848067.358740.png
1341848067.390706 rgb/1341848067.390706.png 1341848067.390723 depth/1341848067.390723.png
1341848067.426869 rgb/1341848067.426869.png 1341848067.426896 depth/1341848067.426896.png
1341848067.458745 rgb/1341848067.458745.png 1341848067.458759 depth/1341848067.458759.png
1341848067.491527 rgb/1341848067.491527.png 1341848067.491567 depth/1341848067.491567.png
1341848067.526659 rgb/1341848067.526659.png 1341848067.526716 depth/1341848067.526716.png
1341848067.558770 rgb/1341848067.558770.png 1341848067.558783 depth/1341848067.558783.png
1341848067.594659 rgb/1341848067.594659.png 1341848067.594669 depth/1341848067.594669.png
1341848067.626656 rgb/1341848067.626656.png 1341848067.626667 depth/1341848067.626667.png
1341848067.658983 rgb/1341848067.658983.png 1341848067.659013 depth/1341848067.659013.png
1341848067.694893 rgb/1341848067.694893.png 1341848067.694912 depth/1341848067.694912.png
1341848067.726732 rgb/1341848067.726732.png 1341848067.727398 depth/1341848067.727398.png
1341848067.758667 rgb/1341848067.758667.png 1341848067.758683 depth/1341848067.758683.png
1341848067.794813 rgb/1341848067.794813.png 1341848067.794832 depth/1341848067.794832.png
1341848067.826795 rgb/1341848067.826795.png 1341848067.826810 depth/1341848067.826810.png
1341848067.862808 rgb/1341848067.862808.png 1341848067.862836 depth/1341848067.862836.png
================================================
FILE: Examples/RGB-D/associations/fr3_office_val.txt
================================================
1341848149.066823 rgb/1341848149.066823.png 1341848149.066840 depth/1341848149.066840.png
1341848149.102697 rgb/1341848149.102697.png 1341848149.102708 depth/1341848149.102708.png
1341848149.134977 rgb/1341848149.134977.png 1341848149.135003 depth/1341848149.135003.png
1341848149.170774 rgb/1341848149.170774.png 1341848149.170801 depth/1341848149.170801.png
1341848149.202906 rgb/1341848149.202906.png 1341848149.203557 depth/1341848149.203557.png
1341848149.234807 rgb/1341848149.234807.png 1341848149.235737 depth/1341848149.235737.png
1341848149.277866 rgb/1341848149.277866.png 1341848149.277886 depth/1341848149.277886.png
1341848149.341858 rgb/1341848149.341858.png 1341848149.341893 depth/1341848149.341893.png
1341848149.402909 rgb/1341848149.402909.png 1341848149.402922 depth/1341848149.402922.png
1341848149.470905 rgb/1341848149.470905.png 1341848149.470949 depth/1341848149.470949.png
1341848149.502903 rgb/1341848149.502903.png 1341848149.502945 depth/1341848149.502945.png
1341848149.538854 rgb/1341848149.538854.png 1341848149.538873 depth/1341848149.538873.png
1341848149.570826 rgb/1341848149.570826.png 1341848149.570945 depth/1341848149.570945.png
1341848149.602772 rgb/1341848149.602772.png 1341848149.602796 depth/1341848149.602796.png
1341848149.638821 rgb/1341848149.638821.png 1341848149.638877 depth/1341848149.638877.png
1341848149.672069 rgb/1341848149.672069.png 1341848149.672090 depth/1341848149.672090.png
1341848149.706860 rgb/1341848149.706860.png 1341848149.707633 depth/1341848149.707633.png
1341848149.738778 rgb/1341848149.738778.png 1341848149.738788 depth/1341848149.738788.png
1341848149.770766 rgb/1341848149.770766.png 1341848149.770783 depth/1341848149.770783.png
1341848149.806957 rgb/1341848149.806957.png 1341848149.806975 depth/1341848149.806975.png
1341848149.838794 rgb/1341848149.838794.png 1341848149.838805 depth/1341848149.838805.png
1341848149.870877 rgb/1341848149.870877.png 1341848149.870896 depth/1341848149.870896.png
1341848149.906729 rgb/1341848149.906729.png 1341848149.907655 depth/1341848149.907655.png
1341848149.938848 rgb/1341848149.938848.png 1341848149.938861 depth/1341848149.938861.png
1341848149.974872 rgb/1341848149.974872.png 1341848149.974893 depth/1341848149.974893.png
1341848150.006810 rgb/1341848150.006810.png 1341848150.006858 depth/1341848150.006858.png
1341848150.038981 rgb/1341848150.038981.png 1341848150.039030 depth/1341848150.039030.png
1341848150.074765 rgb/1341848150.074765.png 1341848150.074813 depth/1341848150.074813.png
1341848150.106812 rgb/1341848150.106812.png 1341848150.106911 depth/1341848150.106911.png
1341848150.142689 rgb/1341848150.142689.png 1341848150.142728 depth/1341848150.142728.png
1341848150.174840 rgb/1341848150.174840.png 1341848150.174876 depth/1341848150.174876.png
1341848150.207021 rgb/1341848150.207021.png 1341848150.207035 depth/1341848150.207035.png
1341848150.242762 rgb/1341848150.242762.png 1341848150.242803 depth/1341848150.242803.png
1341848150.274881 rgb/1341848150.274881.png 1341848150.274891 depth/1341848150.274891.png
1341848150.306915 rgb/1341848150.306915.png 1341848150.306931 depth/1341848150.306931.png
1341848150.342852 rgb/1341848150.342852.png 1341848150.342870 depth/1341848150.342870.png
1341848150.374784 rgb/1341848150.374784.png 1341848150.374802 depth/1341848150.374802.png
1341848150.410799 rgb/1341848150.410799.png 1341848150.410853 depth/1341848150.410853.png
1341848150.442767 rgb/1341848150.442767.png 1341848150.442788 depth/1341848150.442788.png
1341848150.475017 rgb/1341848150.475017.png 1341848150.475667 depth/1341848150.475667.png
1341848150.510959 rgb/1341848150.510959.png 1341848150.510977 depth/1341848150.510977.png
1341848150.543172 rgb/1341848150.543172.png 1341848150.543195 depth/1341848150.543195.png
1341848150.574862 rgb/1341848150.574862.png 1341848150.574871 depth/1341848150.574871.png
1341848150.610694 rgb/1341848150.610694.png 1341848150.610709 depth/1341848150.610709.png
1341848150.642797 rgb/1341848150.642797.png 1341848150.642816 depth/1341848150.642816.png
1341848150.678807 rgb/1341848150.678807.png 1341848150.678884 depth/1341848150.678884.png
1341848150.710756 rgb/1341848150.710756.png 1341848150.710772 depth/1341848150.710772.png
1341848150.742732 rgb/1341848150.742732.png 1341848150.742744 depth/1341848150.742744.png
1341848150.778824 rgb/1341848150.778824.png 1341848150.778847 depth/1341848150.778847.png
1341848150.810830 rgb/1341848150.810830.png 1341848150.810850 depth/1341848150.810850.png
1341848150.842808 rgb/1341848150.842808.png 1341848150.842855 depth/1341848150.842855.png
1341848150.878783 rgb/1341848150.878783.png 1341848150.878829 depth/1341848150.878829.png
1341848150.910764 rgb/1341848150.910764.png 1341848150.910828 depth/1341848150.910828.png
1341848150.947372 rgb/1341848150.947372.png 1341848150.947431 depth/1341848150.947431.png
1341848150.978750 rgb/1341848150.978750.png 1341848150.978774 depth/1341848150.978774.png
1341848151.010858 rgb/1341848151.010858.png 1341848151.010871 depth/1341848151.010871.png
1341848151.046684 rgb/1341848151.046684.png 1341848151.046710 depth/1341848151.046710.png
1341848151.078840 rgb/1341848151.078840.png 1341848151.078859 depth/1341848151.078859.png
1341848151.110918 rgb/1341848151.110918.png 1341848151.110931 depth/1341848151.110931.png
1341848151.146760 rgb/1341848151.146760.png 1341848151.146771 depth/1341848151.146771.png
1341848151.178840 rgb/1341848151.178840.png 1341848151.178912 depth/1341848151.178912.png
1341848151.214772 rgb/1341848151.214772.png 1341848151.214785 depth/1341848151.214785.png
1341848151.246861 rgb/1341848151.246861.png 1341848151.246894 depth/1341848151.246894.png
1341848151.278869 rgb/1341848151.278869.png 1341848151.278881 depth/1341848151.278881.png
1341848151.314829 rgb/1341848151.314829.png 1341848151.314846 depth/1341848151.314846.png
1341848151.346784 rgb/1341848151.346784.png 1341848151.346801 depth/1341848151.346801.png
1341848151.382799 rgb/1341848151.382799.png 1341848151.382817 depth/1341848151.382817.png
1341848151.414826 rgb/1341848151.414826.png 1341848151.414842 depth/1341848151.414842.png
1341848151.447146 rgb/1341848151.447146.png 1341848151.447173 depth/1341848151.447173.png
1341848151.482775 rgb/1341848151.482775.png 1341848151.482789 depth/1341848151.482789.png
1341848151.514689 rgb/1341848151.514689.png 1341848151.514700 depth/1341848151.514700.png
1341848151.546786 rgb/1341848151.546786.png 1341848151.546801 depth/1341848151.546801.png
1341848151.582708 rgb/1341848151.582708.png 1341848151.582718 depth/1341848151.582718.png
1341848151.614865 rgb/1341848151.614865.png 1341848151.615537 depth/1341848151.615537.png
1341848151.650765 rgb/1341848151.650765.png 1341848151.650777 depth/1341848151.650777.png
1341848151.682723 rgb/1341848151.682723.png 1341848151.682738 depth/1341848151.682738.png
1341848151.714803 rgb/1341848151.714803.png 1341848151.714815 depth/1341848151.714815.png
1341848151.753962 rgb/1341848151.753962.png 1341848151.753974 depth/1341848151.753974.png
1341848151.789850 rgb/1341848151.789850.png 1341848151.789864 depth/1341848151.789864.png
1341848151.822446 rgb/1341848151.822446.png 1341848151.823065 depth/1341848151.823065.png
1341848151.857770 rgb/1341848151.857770.png 1341848151.857782 depth/1341848151.857782.png
1341848151.889853 rgb/1341848151.889853.png 1341848151.889866 depth/1341848151.889866.png
1341848151.921969 rgb/1341848151.921969.png 1341848151.921988 depth/1341848151.921988.png
1341848151.958124 rgb/1341848151.958124.png 1341848151.958136 depth/1341848151.958136.png
1341848151.990382 rgb/1341848151.990382.png 1341848151.990401 depth/1341848151.990401.png
1341848152.021736 rgb/1341848152.021736.png 1341848152.021749 depth/1341848152.021749.png
1341848152.057855 rgb/1341848152.057855.png 1341848152.057868 depth/1341848152.057868.png
1341848152.089760 rgb/1341848152.089760.png 1341848152.089810 depth/1341848152.089810.png
1341848152.121861 rgb/1341848152.121861.png 1341848152.121876 depth/1341848152.121876.png
1341848152.157843 rgb/1341848152.157843.png 1341848152.157856 depth/1341848152.157856.png
1341848152.189912 rgb/1341848152.189912.png 1341848152.189945 depth/1341848152.189945.png
1341848152.221732 rgb/1341848152.221732.png 1341848152.221742 depth/1341848152.221742.png
1341848152.257938 rgb/1341848152.257938.png 1341848152.257957 depth/1341848152.257957.png
1341848152.289892 rgb/1341848152.289892.png 1341848152.290412 depth/1341848152.290412.png
1341848152.325735 rgb/1341848152.325735.png 1341848152.325788 depth/1341848152.325788.png
1341848152.357767 rgb/1341848152.357767.png 1341848152.357787 depth/1341848152.357787.png
1341848152.389701 rgb/1341848152.389701.png 1341848152.390206 depth/1341848152.390206.png
1341848152.425865 rgb/1341848152.425865.png 1341848152.425907 depth/1341848152.425907.png
1341848152.457954 rgb/1341848152.457954.png 1341848152.458694 depth/1341848152.458694.png
1341848152.489814 rgb/1341848152.489814.png 1341848152.489851 depth/1341848152.489851.png
1341848152.525817 rgb/1341848152.525817.png 1341848152.525835 depth/1341848152.525835.png
1341848152.557752 rgb/1341848152.557752.png 1341848152.558427 depth/1341848152.558427.png
1341848152.593897 rgb/1341848152.593897.png 1341848152.593922 depth/1341848152.593922.png
1341848152.625767 rgb/1341848152.625767.png 1341848152.625780 depth/1341848152.625780.png
1341848152.661840 rgb/1341848152.661840.png 1341848152.661853 depth/1341848152.661853.png
1341848152.693977 rgb/1341848152.693977.png 1341848152.694003 depth/1341848152.694003.png
1341848152.725768 rgb/1341848152.725768.png 1341848152.725782 depth/1341848152.725782.png
1341848152.793931 rgb/1341848152.793931.png 1341848152.793981 depth/1341848152.793981.png
1341848152.854946 rgb/1341848152.854946.png 1341848152.854970 depth/1341848152.854970.png
1341848152.891028 rgb/1341848152.891028.png 1341848152.891108 depth/1341848152.891108.png
1341848152.922732 rgb/1341848152.922732.png 1341848152.922763 depth/1341848152.922763.png
1341848152.954881 rgb/1341848152.954881.png 1341848152.954892 depth/1341848152.954892.png
1341848152.990741 rgb/1341848152.990741.png 1341848152.990844 depth/1341848152.990844.png
1341848153.022885 rgb/1341848153.022885.png 1341848153.022905 depth/1341848153.022905.png
1341848153.054929 rgb/1341848153.054929.png 1341848153.054952 depth/1341848153.054952.png
1341848153.090747 rgb/1341848153.090747.png 1341848153.090775 depth/1341848153.090775.png
1341848153.122836 rgb/1341848153.122836.png 1341848153.122862 depth/1341848153.122862.png
1341848153.158762 rgb/1341848153.158762.png 1341848153.158776 depth/1341848153.158776.png
1341848153.190741 rgb/1341848153.190741.png 1341848153.190769 depth/1341848153.190769.png
1341848153.258885 rgb/1341848153.258885.png 1341848153.258913 depth/1341848153.258913.png
1341848153.290715 rgb/1341848153.290715.png 1341848153.290745 depth/1341848153.290745.png
1341848153.322774 rgb/1341848153.322774.png 1341848153.322792 depth/1341848153.322792.png
1341848153.358890 rgb/1341848153.358890.png 1341848153.358905 depth/1341848153.358905.png
1341848153.390891 rgb/1341848153.390891.png 1341848153.390915 depth/1341848153.390915.png
1341848153.426855 rgb/1341848153.426855.png 1341848153.426898 depth/1341848153.426898.png
1341848153.458991 rgb/1341848153.458991.png 1341848153.459012 depth/1341848153.459012.png
1341848153.490815 rgb/1341848153.490815.png 1341848153.490830 depth/1341848153.490830.png
1341848153.526800 rgb/1341848153.526800.png 1341848153.526832 depth/1341848153.526832.png
1341848153.558697 rgb/1341848153.558697.png 1341848153.558712 depth/1341848153.558712.png
1341848153.594836 rgb/1341848153.594836.png 1341848153.594854 depth/1341848153.594854.png
1341848153.626784 rgb/1341848153.626784.png 1341848153.626801 depth/1341848153.626801.png
1341848153.658820 rgb/1341848153.658820.png 1341848153.658847 depth/1341848153.658847.png
1341848153.694934 rgb/1341848153.694934.png 1341848153.694948 depth/1341848153.694948.png
1341848153.726981 rgb/1341848153.726981.png 1341848153.727499 depth/1341848153.727499.png
1341848153.794865 rgb/1341848153.794865.png 1341848153.794891 depth/1341848153.794891.png
1341848153.826751 rgb/1341848153.826751.png 1341848153.826762 depth/1341848153.826762.png
1341848153.862912 rgb/1341848153.862912.png 1341848153.862925 depth/1341848153.862925.png
1341848153.894730 rgb/1341848153.894730.png 1341848153.895338 depth/1341848153.895338.png
1341848153.963184 rgb/1341848153.963184.png 1341848153.963206 depth/1341848153.963206.png
1341848153.995018 rgb/1341848153.995018.png 1341848153.995958 depth/1341848153.995958.png
1341848154.034308 rgb/1341848154.034308.png 1341848154.035032 depth/1341848154.035032.png
1341848154.065889 rgb/1341848154.065889.png 1341848154.065953 depth/1341848154.065953.png
1341848154.102447 rgb/1341848154.102447.png 1341848154.102475 depth/1341848154.102475.png
1341848154.133741 rgb/1341848154.133741.png 1341848154.133754 depth/1341848154.133754.png
1341848154.169945 rgb/1341848154.169945.png 1341848154.170576 depth/1341848154.170576.png
1341848154.201842 rgb/1341848154.201842.png 1341848154.201859 depth/1341848154.201859.png
1341848154.233724 rgb/1341848154.233724.png 1341848154.233748 depth/1341848154.233748.png
1341848154.270396 rgb/1341848154.270396.png 1341848154.270408 depth/1341848154.270408.png
1341848154.301840 rgb/1341848154.301840.png 1341848154.301852 depth/1341848154.301852.png
1341848154.333859 rgb/1341848154.333859.png 1341848154.333875 depth/1341848154.333875.png
1341848154.369816 rgb/1341848154.369816.png 1341848154.369840 depth/1341848154.369840.png
1341848154.463148 rgb/1341848154.463148.png 1341848154.463187 depth/1341848154.463187.png
1341848154.498871 rgb/1341848154.498871.png 1341848154.498917 depth/1341848154.498917.png
1341848154.531153 rgb/1341848154.531153.png 1341848154.531174 depth/1341848154.531174.png
1341848154.567126 rgb/1341848154.567126.png 1341848154.567147 depth/1341848154.567147.png
1341848154.598722 rgb/1341848154.598722.png 1341848154.598733 depth/1341848154.598733.png
1341848154.630742 rgb/1341848154.630742.png 1341848154.630755 depth/1341848154.630755.png
1341848154.666878 rgb/1341848154.666878.png 1341848154.666945 depth/1341848154.666945.png
1341848154.698768 rgb/1341848154.698768.png 1341848154.699352 depth/1341848154.699352.png
1341848154.730792 rgb/1341848154.730792.png 1341848154.730867 depth/1341848154.730867.png
1341848154.766738 rgb/1341848154.766738.png 1341848154.766751 depth/1341848154.766751.png
1341848154.798913 rgb/1341848154.798913.png 1341848154.798927 depth/1341848154.798927.png
1341848154.834763 rgb/1341848154.834763.png 1341848154.834782 depth/1341848154.834782.png
1341848154.866760 rgb/1341848154.866760.png 1341848154.866773 depth/1341848154.866773.png
1341848154.898822 rgb/1341848154.898822.png 1341848154.898838 depth/1341848154.898838.png
1341848154.934745 rgb/1341848154.934745.png 1341848154.934790 depth/1341848154.934790.png
1341848154.966947 rgb/1341848154.966947.png 1341848154.966991 depth/1341848154.966991.png
1341848154.998863 rgb/1341848154.998863.png 1341848154.999526 depth/1341848154.999526.png
1341848155.035236 rgb/1341848155.035236.png 1341848155.035254 depth/1341848155.035254.png
1341848155.066760 rgb/1341848155.066760.png 1341848155.067708 depth/1341848155.067708.png
1341848155.102749 rgb/1341848155.102749.png 1341848155.102768 depth/1341848155.102768.png
1341848155.134921 rgb/1341848155.134921.png 1341848155.135647 depth/1341848155.135647.png
1341848155.166807 rgb/1341848155.166807.png 1341848155.166837 depth/1341848155.166837.png
1341848155.209870 rgb/1341848155.209870.png 1341848155.202922 depth/1341848155.202922.png
1341848155.266828 rgb/1341848155.266828.png 1341848155.266927 depth/1341848155.266927.png
1341848155.302895 rgb/1341848155.302895.png 1341848155.302920 depth/1341848155.302920.png
1341848155.334832 rgb/1341848155.334832.png 1341848155.334878 depth/1341848155.334878.png
1341848155.370811 rgb/1341848155.370811.png 1341848155.370838 depth/1341848155.370838.png
1341848155.402780 rgb/1341848155.402780.png 1341848155.402823 depth/1341848155.402823.png
1341848155.434969 rgb/1341848155.434969.png 1341848155.435010 depth/1341848155.435010.png
1341848155.470803 rgb/1341848155.470803.png 1341848155.470834 depth/1341848155.470834.png
1341848155.503099 rgb/1341848155.503099.png 1341848155.503122 depth/1341848155.503122.png
1341848155.534797 rgb/1341848155.534797.png 1341848155.534816 depth/1341848155.534816.png
1341848155.570848 rgb/1341848155.570848.png 1341848155.570898 depth/1341848155.570898.png
1341848155.602904 rgb/1341848155.602904.png 1341848155.602917 depth/1341848155.602917.png
1341848155.638834 rgb/1341848155.638834.png 1341848155.638847 depth/1341848155.638847.png
1341848155.671281 rgb/1341848155.671281.png 1341848155.671301 depth/1341848155.671301.png
1341848155.702854 rgb/1341848155.702854.png 1341848155.702890 depth/1341848155.702890.png
1341848155.738899 rgb/1341848155.738899.png 1341848155.738930 depth/1341848155.738930.png
1341848155.771612 rgb/1341848155.771612.png 1341848155.771649 depth/1341848155.771649.png
1341848155.806718 rgb/1341848155.806718.png 1341848155.806726 depth/1341848155.806726.png
1341848155.839015 rgb/1341848155.839015.png 1341848155.839042 depth/1341848155.839042.png
1341848155.870777 rgb/1341848155.870777.png 1341848155.870798 depth/1341848155.870798.png
1341848155.906868 rgb/1341848155.906868.png 1341848155.906886 depth/1341848155.906886.png
1341848155.938898 rgb/1341848155.938898.png 1341848155.938913 depth/1341848155.938913.png
1341848155.970766 rgb/1341848155.970766.png 1341848155.970779 depth/1341848155.970779.png
1341848156.006744 rgb/1341848156.006744.png 1341848156.006772 depth/1341848156.006772.png
1341848156.038759 rgb/1341848156.038759.png 1341848156.038997 depth/1341848156.038997.png
1341848156.074738 rgb/1341848156.074738.png 1341848156.074751 depth/1341848156.074751.png
1341848156.106768 rgb/1341848156.106768.png 1341848156.106814 depth/1341848156.106814.png
1341848156.138845 rgb/1341848156.138845.png 1341848156.138861 depth/1341848156.138861.png
1341848156.174932 rgb/1341848156.174932.png 1341848156.174950 depth/1341848156.174950.png
1341848156.207279 rgb/1341848156.207279.png 1341848156.207303 depth/1341848156.207303.png
1341848156.238750 rgb/1341848156.238750.png 1341848156.238767 depth/1341848156.238767.png
1341848156.274871 rgb/1341848156.274871.png 1341848156.274884 depth/1341848156.274884.png
1341848156.342805 rgb/1341848156.342805.png 1341848156.342830 depth/1341848156.342830.png
1341848156.374707 rgb/1341848156.374707.png 1341848156.374747 depth/1341848156.374747.png
1341848156.406805 rgb/1341848156.406805.png 1341848156.406853 depth/1341848156.406853.png
1341848156.442657 rgb/1341848156.442657.png 1341848156.442720 depth/1341848156.442720.png
1341848156.474862 rgb/1341848156.474862.png 1341848156.474877 depth/1341848156.474877.png
1341848156.506819 rgb/1341848156.506819.png 1341848156.507603 depth/1341848156.507603.png
1341848156.542898 rgb/1341848156.542898.png 1341848156.542928 depth/1341848156.542928.png
1341848156.574830 rgb/1341848156.574830.png 1341848156.574895 depth/1341848156.574895.png
1341848156.610846 rgb/1341848156.610846.png 1341848156.610872 depth/1341848156.610872.png
1341848156.643458 rgb/1341848156.643458.png 1341848156.643476 depth/1341848156.643476.png
1341848156.674747 rgb/1341848156.674747.png 1341848156.674772 depth/1341848156.674772.png
1341848156.710769 rgb/1341848156.710769.png 1341848156.710807 depth/1341848156.710807.png
1341848156.742933 rgb/1341848156.742933.png 1341848156.742973 depth/1341848156.742973.png
1341848156.778725 rgb/1341848156.778725.png 1341848156.778748 depth/1341848156.778748.png
1341848156.810836 rgb/1341848156.810836.png 1341848156.810846 depth/1341848156.810846.png
1341848156.843223 rgb/1341848156.843223.png 1341848156.843233 depth/1341848156.843233.png
1341848156.878714 rgb/1341848156.878714.png 1341848156.878759 depth/1341848156.878759.png
1341848156.910766 rgb/1341848156.910766.png 1341848156.910782 depth/1341848156.910782.png
1341848156.942797 rgb/1341848156.942797.png 1341848156.942809 depth/1341848156.942809.png
1341848156.978827 rgb/1341848156.978827.png 1341848156.978840 depth/1341848156.978840.png
1341848157.010816 rgb/1341848157.010816.png 1341848157.010841 depth/1341848157.010841.png
1341848157.046853 rgb/1341848157.046853.png 1341848157.046868 depth/1341848157.046868.png
1341848157.078893 rgb/1341848157.078893.png 1341848157.078902 depth/1341848157.078902.png
1341848157.110834 rgb/1341848157.110834.png 1341848157.110855 depth/1341848157.110855.png
1341848157.146936 rgb/1341848157.146936.png 1341848157.146965 depth/1341848157.146965.png
1341848157.178766 rgb/1341848157.178766.png 1341848157.178786 depth/1341848157.178786.png
1341848157.210843 rgb/1341848157.210843.png 1341848157.210882 depth/1341848157.210882.png
1341848157.246913 rgb/1341848157.246913.png 1341848157.246930 depth/1341848157.246930.png
1341848157.278836 rgb/1341848157.278836.png 1341848157.278918 depth/1341848157.278918.png
1341848157.314784 rgb/1341848157.314784.png 1341848157.314823 depth/1341848157.314823.png
1341848157.346896 rgb/1341848157.346896.png 1341848157.346931 depth/1341848157.346931.png
1341848157.378813 rgb/1341848157.378813.png 1341848157.378859 depth/1341848157.378859.png
1341848157.414741 rgb/1341848157.414741.png 1341848157.414781 depth/1341848157.414781.png
1341848157.446839 rgb/1341848157.446839.png 1341848157.446955 depth/1341848157.446955.png
1341848157.478906 rgb/1341848157.478906.png 1341848157.479185 depth/1341848157.479185.png
1341848157.514883 rgb/1341848157.514883.png 1341848157.515353 depth/1341848157.515353.png
1341848157.546769 rgb/1341848157.546769.png 1341848157.546828 depth/1341848157.546828.png
1341848157.582926 rgb/1341848157.582926.png 1341848157.582936 depth/1341848157.582936.png
1341848157.614748 rgb/1341848157.614748.png 1341848157.614757 depth/1341848157.614757.png
1341848157.646960 rgb/1341848157.646960.png 1341848157.647000 depth/1341848157.647000.png
1341848157.682790 rgb/1341848157.682790.png 1341848157.682801 depth/1341848157.682801.png
1341848157.714975 rgb/1341848157.714975.png 1341848157.714987 depth/1341848157.714987.png
1341848157.750708 rgb/1341848157.750708.png 1341848157.750747 depth/1341848157.750747.png
1341848157.782758 rgb/1341848157.782758.png 1341848157.782770 depth/1341848157.782770.png
1341848157.814919 rgb/1341848157.814919.png 1341848157.815970 depth/1341848157.815970.png
1341848157.850677 rgb/1341848157.850677.png 1341848157.850692 depth/1341848157.850692.png
1341848157.882761 rgb/1341848157.882761.png 1341848157.882775 depth/1341848157.882775.png
1341848157.914774 rgb/1341848157.914774.png 1341848157.914790 depth/1341848157.914790.png
1341848157.950731 rgb/1341848157.950731.png 1341848157.950744 depth/1341848157.950744.png
1341848157.982725 rgb/1341848157.982725.png 1341848157.982740 depth/1341848157.982740.png
1341848158.018736 rgb/1341848158.018736.png 1341848158.018749 depth/1341848158.018749.png
1341848158.083079 rgb/1341848158.083079.png 1341848158.083110 depth/1341848158.083110.png
1341848158.118854 rgb/1341848158.118854.png 1341848158.118870 depth/1341848158.118870.png
1341848158.182918 rgb/1341848158.182918.png 1341848158.182933 depth/1341848158.182933.png
1341848158.218795 rgb/1341848158.218795.png 1341848158.218813 depth/1341848158.218813.png
1341848158.250745 rgb/1341848158.250745.png 1341848158.250758 depth/1341848158.250758.png
1341848158.286804 rgb/1341848158.286804.png 1341848158.286827 depth/1341848158.286827.png
1341848158.318738 rgb/1341848158.318738.png 1341848158.318748 depth/1341848158.318748.png
1341848158.350718 rgb/1341848158.350718.png 1341848158.350732 depth/1341848158.350732.png
1341848158.387933 rgb/1341848158.387933.png 1341848158.387995 depth/1341848158.387995.png
1341848158.418868 rgb/1341848158.418868.png 1341848158.419496 depth/1341848158.419496.png
1341848158.450851 rgb/1341848158.450851.png 1341848158.450873 depth/1341848158.450873.png
1341848158.486805 rgb/1341848158.486805.png 1341848158.486853 depth/1341848158.486853.png
1341848158.518859 rgb/1341848158.518859.png 1341848158.518876 depth/1341848158.518876.png
1341848158.554692 rgb/1341848158.554692.png 1341848158.554705 depth/1341848158.554705.png
1341848158.586776 rgb/1341848158.586776.png 1341848158.586810 depth/1341848158.586810.png
1341848158.618875 rgb/1341848158.618875.png 1341848158.618891 depth/1341848158.618891.png
1341848158.654943 rgb/1341848158.654943.png 1341848158.654995 depth/1341848158.654995.png
1341848158.686821 rgb/1341848158.686821.png 1341848158.686836 depth/1341848158.686836.png
1341848158.718781 rgb/1341848158.718781.png 1341848158.718800 depth/1341848158.718800.png
1341848158.755265 rgb/1341848158.755265.png 1341848158.755282 depth/1341848158.755282.png
1341848158.786916 rgb/1341848158.786916.png 1341848158.786940 depth/1341848158.786940.png
1341848158.822796 rgb/1341848158.822796.png 1341848158.822827 depth/1341848158.822827.png
1341848158.854983 rgb/1341848158.854983.png 1341848158.855000 depth/1341848158.855000.png
1341848158.886874 rgb/1341848158.886874.png 1341848158.887512 depth/1341848158.887512.png
1341848158.922780 rgb/1341848158.922780.png 1341848158.922792 depth/1341848158.922792.png
1341848158.954834 rgb/1341848158.954834.png 1341848158.954851 depth/1341848158.954851.png
1341848158.990860 rgb/1341848158.990860.png 1341848158.990875 depth/1341848158.990875.png
1341848159.022769 rgb/1341848159.022769.png 1341848159.022785 depth/1341848159.022785.png
1341848159.055290 rgb/1341848159.055290.png 1341848159.055313 depth/1341848159.055313.png
1341848159.090841 rgb/1341848159.090841.png 1341848159.090857 depth/1341848159.090857.png
1341848159.122756 rgb/1341848159.122756.png 1341848159.122772 depth/1341848159.122772.png
1341848159.154804 rgb/1341848159.154804.png 1341848159.154824 depth/1341848159.154824.png
1341848159.190705 rgb/1341848159.190705.png 1341848159.190729 depth/1341848159.190729.png
1341848159.222742 rgb/1341848159.222742.png 1341848159.222757 depth/1341848159.222757.png
1341848159.258924 rgb/1341848159.258924.png 1341848159.258938 depth/1341848159.258938.png
1341848159.291030 rgb/1341848159.291030.png 1341848159.291048 depth/1341848159.291048.png
1341848159.322862 rgb/1341848159.322862.png 1341848159.323059 depth/1341848159.323059.png
1341848159.358817 rgb/1341848159.358817.png 1341848159.358831 depth/1341848159.358831.png
1341848159.390737 rgb/1341848159.390737.png 1341848159.390757 depth/1341848159.390757.png
1341848159.422816 rgb/1341848159.422816.png 1341848159.422859 depth/1341848159.422859.png
1341848159.458808 rgb/1341848159.458808.png 1341848159.458840 depth/1341848159.458840.png
1341848159.490804 rgb/1341848159.490804.png 1341848159.491469 depth/1341848159.491469.png
1341848159.526950 rgb/1341848159.526950.png 1341848159.526963 depth/1341848159.526963.png
1341848159.558785 rgb/1341848159.558785.png 1341848159.559419 depth/1341848159.559419.png
1341848159.590787 rgb/1341848159.590787.png 1341848159.590826 depth/1341848159.590826.png
1341848159.626836 rgb/1341848159.626836.png 1341848159.626867 depth/1341848159.626867.png
1341848159.658886 rgb/1341848159.658886.png 1341848159.658910 depth/1341848159.658910.png
1341848159.690794 rgb/1341848159.690794.png 1341848159.690820 depth/1341848159.690820.png
1341848159.726780 rgb/1341848159.726780.png 1341848159.726819 depth/1341848159.726819.png
1341848159.759125 rgb/1341848159.759125.png 1341848159.759144 depth/1341848159.759144.png
1341848159.794870 rgb/1341848159.794870.png 1341848159.794883 depth/1341848159.794883.png
1341848159.826708 rgb/1341848159.826708.png 1341848159.826726 depth/1341848159.826726.png
1341848159.858901 rgb/1341848159.858901.png 1341848159.858916 depth/1341848159.858916.png
1341848159.894858 rgb/1341848159.894858.png 1341848159.894871 depth/1341848159.894871.png
1341848159.926828 rgb/1341848159.926828.png 1341848159.926845 depth/1341848159.926845.png
1341848159.962911 rgb/1341848159.962911.png 1341848159.962925 depth/1341848159.962925.png
1341848159.994764 rgb/1341848159.994764.png 1341848159.994773 depth/1341848159.994773.png
1341848160.026703 rgb/1341848160.026703.png 1341848160.026714 depth/1341848160.026714.png
1341848160.062822 rgb/1341848160.062822.png 1341848160.062831 depth/1341848160.062831.png
1341848160.094831 rgb/1341848160.094831.png 1341848160.094840 depth/1341848160.094840.png
1341848160.126793 rgb/1341848160.126793.png 1341848160.126817 depth/1341848160.126817.png
1341848160.162868 rgb/1341848160.162868.png 1341848160.162915 depth/1341848160.162915.png
1341848160.194891 rgb/1341848160.194891.png 1341848160.195552 depth/1341848160.195552.png
1341848160.230921 rgb/1341848160.230921.png 1341848160.230935 depth/1341848160.230935.png
1341848160.263051 rgb/1341848160.263051.png 1341848160.263047 depth/1341848160.263047.png
1341848160.294866 rgb/1341848160.294866.png 1341848160.294882 depth/1341848160.294882.png
1341848160.330780 rgb/1341848160.330780.png 1341848160.330813 depth/1341848160.330813.png
1341848160.362748 rgb/1341848160.362748.png 1341848160.362759 depth/1341848160.362759.png
1341848160.394788 rgb/1341848160.394788.png 1341848160.394804 depth/1341848160.394804.png
1341848160.430712 rgb/1341848160.430712.png 1341848160.430742 depth/1341848160.430742.png
1341848160.462944 rgb/1341848160.462944.png 1341848160.463020 depth/1341848160.463020.png
1341848160.498941 rgb/1341848160.498941.png 1341848160.498976 depth/1341848160.498976.png
1341848160.530917 rgb/1341848160.530917.png 1341848160.530981 depth/1341848160.530981.png
1341848160.562788 rgb/1341848160.562788.png 1341848160.562799 depth/1341848160.562799.png
1341848160.598712 rgb/1341848160.598712.png 1341848160.598724 depth/1341848160.598724.png
1341848160.630703 rgb/1341848160.630703.png 1341848160.630733 depth/1341848160.630733.png
1341848160.662998 rgb/1341848160.662998.png 1341848160.663010 depth/1341848160.663010.png
1341848160.698981 rgb/1341848160.698981.png 1341848160.699002 depth/1341848160.699002.png
1341848160.730773 rgb/1341848160.730773.png 1341848160.730783 depth/1341848160.730783.png
1341848160.766902 rgb/1341848160.766902.png 1341848160.766911 depth/1341848160.766911.png
1341848160.798913 rgb/1341848160.798913.png 1341848160.798933 depth/1341848160.798933.png
1341848160.830801 rgb/1341848160.830801.png 1341848160.830837 depth/1341848160.830837.png
1341848160.866791 rgb/1341848160.866791.png 1341848160.866808 depth/1341848160.866808.png
1341848160.898719 rgb/1341848160.898719.png 1341848160.898733 depth/1341848160.898733.png
1341848160.930849 rgb/1341848160.930849.png 1341848160.931523 depth/1341848160.931523.png
1341848160.966815 rgb/1341848160.966815.png 1341848160.966836 depth/1341848160.966836.png
1341848160.998726 rgb/1341848160.998726.png 1341848160.998739 depth/1341848160.998739.png
1341848161.034749 rgb/1341848161.034749.png 1341848161.034765 depth/1341848161.034765.png
1341848161.066799 rgb/1341848161.066799.png 1341848161.066816 depth/1341848161.066816.png
1341848161.098907 rgb/1341848161.098907.png 1341848161.098927 depth/1341848161.098927.png
1341848161.134830 rgb/1341848161.134830.png 1341848161.134864 depth/1341848161.134864.png
1341848161.166996 rgb/1341848161.166996.png 1341848161.167929 depth/1341848161.167929.png
1341848161.202769 rgb/1341848161.202769.png 1341848161.202788 depth/1341848161.202788.png
1341848161.234838 rgb/1341848161.234838.png 1341848161.234855 depth/1341848161.234855.png
1341848161.266797 rgb/1341848161.266797.png 1341848161.266821 depth/1341848161.266821.png
1341848161.302737 rgb/1341848161.302737.png 1341848161.302760 depth/1341848161.302760.png
1341848161.334795 rgb/1341848161.334795.png 1341848161.334813 depth/1341848161.334813.png
1341848161.366834 rgb/1341848161.366834.png 1341848161.366883 depth/1341848161.366883.png
1341848161.434756 rgb/1341848161.434756.png 1341848161.434768 depth/1341848161.434768.png
1341848161.470745 rgb/1341848161.470745.png 1341848161.470799 depth/1341848161.470799.png
1341848161.502853 rgb/1341848161.502853.png 1341848161.502864 depth/1341848161.502864.png
1341848161.534845 rgb/1341848161.534845.png 1341848161.534856 depth/1341848161.534856.png
1341848161.570776 rgb/1341848161.570776.png 1341848161.570792 depth/1341848161.570792.png
1341848161.602903 rgb/1341848161.602903.png 1341848161.602913 depth/1341848161.602913.png
1341848161.670859 rgb/1341848161.670859.png 1341848161.670896 depth/1341848161.670896.png
1341848161.702844 rgb/1341848161.702844.png 1341848161.702866 depth/1341848161.702866.png
1341848161.738842 rgb/1341848161.738842.png 1341848161.738879 depth/1341848161.738879.png
1341848161.770697 rgb/1341848161.770697.png 1341848161.770708 depth/1341848161.770708.png
1341848161.802764 rgb/1341848161.802764.png 1341848161.802785 depth/1341848161.802785.png
1341848161.838669 rgb/1341848161.838669.png 1341848161.838680 depth/1341848161.838680.png
1341848161.870852 rgb/1341848161.870852.png 1341848161.870862 depth/1341848161.870862.png
1341848161.902867 rgb/1341848161.902867.png 1341848161.902880 depth/1341848161.902880.png
1341848161.938688 rgb/1341848161.938688.png 1341848161.938735 depth/1341848161.938735.png
1341848161.970719 rgb/1341848161.970719.png 1341848161.970736 depth/1341848161.970736.png
1341848162.006825 rgb/1341848162.006825.png 1341848162.006838 depth/1341848162.006838.png
1341848162.038732 rgb/1341848162.038732.png 1341848162.038745 depth/1341848162.038745.png
1341848162.070890 rgb/1341848162.070890.png 1341848162.070925 depth/1341848162.070925.png
1341848162.106900 rgb/1341848162.106900.png 1341848162.106909 depth/1341848162.106909.png
1341848162.138762 rgb/1341848162.138762.png 1341848162.138777 depth/1341848162.138777.png
1341848162.174808 rgb/1341848162.174808.png 1341848162.174873 depth/1341848162.174873.png
1341848162.206857 rgb/1341848162.206857.png 1341848162.206873 depth/1341848162.206873.png
1341848162.238754 rgb/1341848162.238754.png 1341848162.238786 depth/1341848162.238786.png
1341848162.274812 rgb/1341848162.274812.png 1341848162.274822 depth/1341848162.274822.png
1341848162.306796 rgb/1341848162.306796.png 1341848162.306813 depth/1341848162.306813.png
1341848162.338764 rgb/1341848162.338764.png 1341848162.338788 depth/1341848162.338788.png
1341848162.374731 rgb/1341848162.374731.png 1341848162.374748 depth/1341848162.374748.png
1341848162.406929 rgb/1341848162.406929.png 1341848162.406949 depth/1341848162.406949.png
1341848162.442899 rgb/1341848162.442899.png 1341848162.442966 depth/1341848162.442966.png
1341848162.474825 rgb/1341848162.474825.png 1341848162.474856 depth/1341848162.474856.png
1341848162.506688 rgb/1341848162.506688.png 1341848162.506714 depth/1341848162.506714.png
1341848162.542701 rgb/1341848162.542701.png 1341848162.542711 depth/1341848162.542711.png
1341848162.574897 rgb/1341848162.574897.png 1341848162.574917 depth/1341848162.574917.png
1341848162.607766 rgb/1341848162.607766.png 1341848162.608485 depth/1341848162.608485.png
1341848162.642853 rgb/1341848162.642853.png 1341848162.642869 depth/1341848162.642869.png
1341848162.674886 rgb/1341848162.674886.png 1341848162.674903 depth/1341848162.674903.png
1341848162.710751 rgb/1341848162.710751.png 1341848162.710769 depth/1341848162.710769.png
1341848162.742823 rgb/1341848162.742823.png 1341848162.742882 depth/1341848162.742882.png
1341848162.774907 rgb/1341848162.774907.png 1341848162.774925 depth/1341848162.774925.png
1341848162.810709 rgb/1341848162.810709.png 1341848162.810721 depth/1341848162.810721.png
1341848162.842849 rgb/1341848162.842849.png 1341848162.843663 depth/1341848162.843663.png
1341848162.874821 rgb/1341848162.874821.png 1341848162.874837 depth/1341848162.874837.png
1341848162.910700 rgb/1341848162.910700.png 1341848162.910710 depth/1341848162.910710.png
1341848162.979216 rgb/1341848162.979216.png 1341848162.979251 depth/1341848162.979251.png
1341848163.010779 rgb/1341848163.010779.png 1341848163.010798 depth/1341848163.010798.png
1341848163.042805 rgb/1341848163.042805.png 1341848163.043395 depth/1341848163.043395.png
1341848163.078878 rgb/1341848163.078878.png 1341848163.078902 depth/1341848163.078902.png
1341848163.110813 rgb/1341848163.110813.png 1341848163.110833 depth/1341848163.110833.png
1341848163.142847 rgb/1341848163.142847.png 1341848163.142860 depth/1341848163.142860.png
1341848163.179133 rgb/1341848163.179133.png 1341848163.179159 depth/1341848163.179159.png
1341848163.210686 rgb/1341848163.210686.png 1341848163.210697 depth/1341848163.210697.png
1341848163.246905 rgb/1341848163.246905.png 1341848163.246918 depth/1341848163.246918.png
1341848163.279126 rgb/1341848163.279126.png 1341848163.279145 depth/1341848163.279145.png
1341848163.310679 rgb/1341848163.310679.png 1341848163.310690 depth/1341848163.310690.png
1341848163.346833 rgb/1341848163.346833.png 1341848163.346842 depth/1341848163.346842.png
1341848163.379093 rgb/1341848163.379093.png 1341848163.379107 depth/1341848163.379107.png
1341848163.414760 rgb/1341848163.414760.png 1341848163.414780 depth/1341848163.414780.png
1341848163.447505 rgb/1341848163.447505.png 1341848163.447533 depth/1341848163.447533.png
1341848163.479147 rgb/1341848163.479147.png 1341848163.480026 depth/1341848163.480026.png
1341848163.514790 rgb/1341848163.514790.png 1341848163.514803 depth/1341848163.514803.png
1341848163.546891 rgb/1341848163.546891.png 1341848163.546908 depth/1341848163.546908.png
1341848163.578968 rgb/1341848163.578968.png 1341848163.578983 depth/1341848163.578983.png
1341848163.614905 rgb/1341848163.614905.png 1341848163.614960 depth/1341848163.614960.png
1341848163.646967 rgb/1341848163.646967.png 1341848163.647613 depth/1341848163.647613.png
1341848163.682840 rgb/1341848163.682840.png 1341848163.683769 depth/1341848163.683769.png
1341848163.715380 rgb/1341848163.715380.png 1341848163.715976 depth/1341848163.715976.png
1341848163.748292 rgb/1341848163.748292.png 1341848163.750108 depth/1341848163.750108.png
1341848163.782940 rgb/1341848163.782940.png 1341848163.782955 depth/1341848163.782955.png
1341848163.815079 rgb/1341848163.815079.png 1341848163.815323 depth/1341848163.815323.png
1341848163.847130 rgb/1341848163.847130.png 1341848163.847751 depth/1341848163.847751.png
1341848163.883764 rgb/1341848163.883764.png 1341848163.884777 depth/1341848163.884777.png
1341848163.951866 rgb/1341848163.951866.png 1341848163.952722 depth/1341848163.952722.png
1341848163.982991 rgb/1341848163.982991.png 1341848163.983696 depth/1341848163.983696.png
1341848164.014820 rgb/1341848164.014820.png 1341848164.014846 depth/1341848164.014846.png
1341848164.050756 rgb/1341848164.050756.png 1341848164.051023 depth/1341848164.051023.png
1341848164.082904 rgb/1341848164.082904.png 1341848164.083565 depth/1341848164.083565.png
1341848164.121798 rgb/1341848164.121798.png 1341848164.121851 depth/1341848164.121851.png
1341848164.182798 rgb/1341848164.182798.png 1341848164.182813 depth/1341848164.182813.png
1341848164.218949 rgb/1341848164.218949.png 1341848164.218965 depth/1341848164.218965.png
1341848164.250726 rgb/1341848164.250726.png 1341848164.250736 depth/1341848164.250736.png
1341848164.282807 rgb/1341848164.282807.png 1341848164.282835 depth/1341848164.282835.png
1341848164.318737 rgb/1341848164.318737.png 1341848164.319274 depth/1341848164.319274.png
1341848164.350869 rgb/1341848164.350869.png 1341848164.351509 depth/1341848164.351509.png
1341848164.386807 rgb/1341848164.386807.png 1341848164.386878 depth/1341848164.386878.png
1341848164.418758 rgb/1341848164.418758.png 1341848164.418784 depth/1341848164.418784.png
1341848164.451050 rgb/1341848164.451050.png 1341848164.451081 depth/1341848164.451081.png
1341848164.486742 rgb/1341848164.486742.png 1341848164.486768 depth/1341848164.486768.png
1341848164.518795 rgb/1341848164.518795.png 1341848164.518809 depth/1341848164.518809.png
1341848164.550805 rgb/1341848164.550805.png 1341848164.550838 depth/1341848164.550838.png
1341848164.586921 rgb/1341848164.586921.png 1341848164.587003 depth/1341848164.587003.png
1341848164.618941 rgb/1341848164.618941.png 1341848164.618964 depth/1341848164.618964.png
1341848164.654712 rgb/1341848164.654712.png 1341848164.654762 depth/1341848164.654762.png
1341848164.686768 rgb/1341848164.686768.png 1341848164.686783 depth/1341848164.686783.png
1341848164.718784 rgb/1341848164.718784.png 1341848164.718830 depth/1341848164.718830.png
1341848164.754825 rgb/1341848164.754825.png 1341848164.754838 depth/1341848164.754838.png
1341848164.786794 rgb/1341848164.786794.png 1341848164.787064 depth/1341848164.787064.png
1341848164.818801 rgb/1341848164.818801.png 1341848164.818824 depth/1341848164.818824.png
1341848164.854945 rgb/1341848164.854945.png 1341848164.854973 depth/1341848164.854973.png
1341848164.886833 rgb/1341848164.886833.png 1341848164.886842 depth/1341848164.886842.png
1341848164.922673 rgb/1341848164.922673.png 1341848164.922689 depth/1341848164.922689.png
1341848164.954891 rgb/1341848164.954891.png 1341848164.954903 depth/1341848164.954903.png
1341848164.986854 rgb/1341848164.986854.png 1341848164.986876 depth/1341848164.986876.png
1341848165.022907 rgb/1341848165.022907.png 1341848165.022925 depth/1341848165.022925.png
1341848165.054958 rgb/1341848165.054958.png 1341848165.054990 depth/1341848165.054990.png
1341848165.086867 rgb/1341848165.086867.png 1341848165.086892 depth/1341848165.086892.png
1341848165.122738 rgb/1341848165.122738.png 1341848165.122818 depth/1341848165.122818.png
1341848165.154778 rgb/1341848165.154778.png 1341848165.154947 depth/1341848165.154947.png
1341848165.190741 rgb/1341848165.190741.png 1341848165.190775 depth/1341848165.190775.png
1341848165.222795 rgb/1341848165.222795.png 1341848165.222821 depth/1341848165.222821.png
1341848165.254753 rgb/1341848165.254753.png 1341848165.254772 depth/1341848165.254772.png
1341848165.290861 rgb/1341848165.290861.png 1341848165.290910 depth/1341848165.290910.png
1341848165.322723 rgb/1341848165.322723.png 1341848165.322752 depth/1341848165.322752.png
1341848165.354808 rgb/1341848165.354808.png 1341848165.354836 depth/1341848165.354836.png
1341848165.390763 rgb/1341848165.390763.png 1341848165.390780 depth/1341848165.390780.png
1341848165.422788 rgb/1341848165.422788.png 1341848165.422807 depth/1341848165.422807.png
1341848165.458783 rgb/1341848165.458783.png 1341848165.458797 depth/1341848165.458797.png
1341848165.490740 rgb/1341848165.490740.png 1341848165.490752 depth/1341848165.490752.png
1341848165.522759 rgb/1341848165.522759.png 1341848165.522771 depth/1341848165.522771.png
1341848165.558825 rgb/1341848165.558825.png 1341848165.558840 depth/1341848165.558840.png
1341848165.590750 rgb/1341848165.590750.png 1341848165.590798 depth/1341848165.590798.png
1341848165.626731 rgb/1341848165.626731.png 1341848165.626748 depth/1341848165.626748.png
1341848165.658757 rgb/1341848165.658757.png 1341848165.658771 depth/1341848165.658771.png
1341848165.690734 rgb/1341848165.690734.png 1341848165.690746 depth/1341848165.690746.png
1341848165.726911 rgb/1341848165.726911.png 1341848165.726951 depth/1341848165.726951.png
1341848165.758729 rgb/1341848165.758729.png 1341848165.758740 depth/1341848165.758740.png
1341848165.790707 rgb/1341848165.790707.png 1341848165.790744 depth/1341848165.790744.png
1341848165.826759 rgb/1341848165.826759.png 1341848165.826778 depth/1341848165.826778.png
1341848165.858701 rgb/1341848165.858701.png 1341848165.858716 depth/1341848165.858716.png
1341848165.894770 rgb/1341848165.894770.png 1341848165.894784 depth/1341848165.894784.png
1341848165.926790 rgb/1341848165.926790.png 1341848165.926807 depth/1341848165.926807.png
1341848165.958997 rgb/1341848165.958997.png 1341848165.959008 depth/1341848165.959008.png
1341848165.994928 rgb/1341848165.994928.png 1341848165.994967 depth/1341848165.994967.png
1341848166.027159 rgb/1341848166.027159.png 1341848166.027788 depth/1341848166.027788.png
1341848166.094950 rgb/1341848166.094950.png 1341848166.094972 depth/1341848166.094972.png
1341848166.126902 rgb/1341848166.126902.png 1341848166.126951 depth/1341848166.126951.png
1341848166.162670 rgb/1341848166.162670.png 1341848166.162682 depth/1341848166.162682.png
1341848166.194932 rgb/1341848166.194932.png 1341848166.194990 depth/1341848166.194990.png
1341848166.226888 rgb/1341848166.226888.png 1341848166.226943 depth/1341848166.226943.png
1341848166.262772 rgb/1341848166.262772.png 1341848166.262819 depth/1341848166.262819.png
1341848166.294738 rgb/1341848166.294738.png 1341848166.294750 depth/1341848166.294750.png
1341848166.326755 rgb/1341848166.326755.png 1341848166.326769 depth/1341848166.326769.png
1341848166.362731 rgb/1341848166.362731.png 1341848166.362743 depth/1341848166.362743.png
1341848166.401837 rgb/1341848166.401837.png 1341848166.401856 depth/1341848166.401856.png
1341848166.433930 rgb/1341848166.433930.png 1341848166.433947 depth/1341848166.433947.png
1341848166.470537 rgb/1341848166.470537.png 1341848166.471219 depth/1341848166.471219.png
1341848166.502542 rgb/1341848166.502542.png 1341848166.502601 depth/1341848166.502601.png
1341848166.533929 rgb/1341848166.533929.png 1341848166.533938 depth/1341848166.533938.png
1341848166.569828 rgb/1341848166.569828.png 1341848166.569884 depth/1341848166.569884.png
1341848166.601817 rgb/1341848166.601817.png 1341848166.601835 depth/1341848166.601835.png
1341848166.633713 rgb/1341848166.633713.png 1341848166.633729 depth/1341848166.633729.png
1341848166.669876 rgb/1341848166.669876.png 1341848166.670815 depth/1341848166.670815.png
1341848166.701918 rgb/1341848166.701918.png 1341848166.701957 depth/1341848166.701957.png
1341848166.734072 rgb/1341848166.734072.png 1341848166.734281 depth/1341848166.734281.png
1341848166.770922 rgb/1341848166.770922.png 1341848166.771241 depth/1341848166.771241.png
1341848166.801847 rgb/1341848166.801847.png 1341848166.801881 depth/1341848166.801881.png
1341848166.837782 rgb/1341848166.837782.png 1341848166.837795 depth/1341848166.837795.png
1341848166.869763 rgb/1341848166.869763.png 1341848166.869774 depth/1341848166.869774.png
1341848166.901822 rgb/1341848166.901822.png 1341848166.901837 depth/1341848166.901837.png
1341848166.937808 rgb/1341848166.937808.png 1341848166.937817 depth/1341848166.937817.png
1341848166.969795 rgb/1341848166.969795.png 1341848166.969892 depth/1341848166.969892.png
1341848167.001793 rgb/1341848167.001793.png 1341848167.001823 depth/1341848167.001823.png
1341848167.037886 rgb/1341848167.037886.png 1341848167.037896 depth/1341848167.037896.png
1341848167.069805 rgb/1341848167.069805.png 1341848167.069817 depth/1341848167.069817.png
1341848167.105919 rgb/1341848167.105919.png 1341848167.105934 depth/1341848167.105934.png
1341848167.137651 rgb/1341848167.137651.png 1341848167.137665 depth/1341848167.137665.png
1341848167.169757 rgb/1341848167.169757.png 1341848167.169770 depth/1341848167.169770.png
1341848167.205756 rgb/1341848167.205756.png 1341848167.205774 depth/1341848167.205774.png
1341848167.237953 rgb/1341848167.237953.png 1341848167.238402 depth/1341848167.238402.png
1341848167.273788 rgb/1341848167.273788.png 1341848167.273824 depth/1341848167.273824.png
1341848167.305856 rgb/1341848167.305856.png 1341848167.305883 depth/1341848167.305883.png
1341848167.337781 rgb/1341848167.337781.png 1341848167.337795 depth/1341848167.337795.png
1341848167.373840 rgb/1341848167.373840.png 1341848167.373853 depth/1341848167.373853.png
1341848167.405669 rgb/1341848167.405669.png 1341848167.405750 depth/1341848167.405750.png
1341848167.441785 rgb/1341848167.441785.png 1341848167.441800 depth/1341848167.441800.png
1341848167.473968 rgb/1341848167.473968.png 1341848167.473999 depth/1341848167.473999.png
1341848167.505889 rgb/1341848167.505889.png 1341848167.505916 depth/1341848167.505916.png
1341848167.542111 rgb/1341848167.542111.png 1341848167.542128 depth/1341848167.542128.png
1341848167.574229 rgb/1341848167.574229.png 1341848167.574243 depth/1341848167.574243.png
1341848167.609887 rgb/1341848167.609887.png 1341848167.609902 depth/1341848167.609902.png
1341848167.641898 rgb/1341848167.641898.png 1341848167.642538 depth/1341848167.642538.png
1341848167.673748 rgb/1341848167.673748.png 1341848167.673761 depth/1341848167.673761.png
1341848167.709849 rgb/1341848167.709849.png 1341848167.709866 depth/1341848167.709866.png
1341848167.741720 rgb/1341848167.741720.png 1341848167.741746 depth/1341848167.741746.png
1341848167.777830 rgb/1341848167.777830.png 1341848167.777866 depth/1341848167.777866.png
1341848167.809866 rgb/1341848167.809866.png 1341848167.809944 depth/1341848167.809944.png
1341848167.841777 rgb/1341848167.841777.png 1341848167.841816 depth/1341848167.841816.png
1341848167.877843 rgb/1341848167.877843.png 1341848167.877856 depth/1341848167.877856.png
1341848167.909736 rgb/1341848167.909736.png 1341848167.909816 depth/1341848167.909816.png
1341848167.945835 rgb/1341848167.945835.png 1341848167.945862 depth/1341848167.945862.png
1341848167.977929 rgb/1341848167.977929.png 1341848167.978434 depth/1341848167.978434.png
1341848168.009789 rgb/1341848168.009789.png 1341848168.009814 depth/1341848168.009814.png
1341848168.046126 rgb/1341848168.046126.png 1341848168.046175 depth/1341848168.046175.png
1341848168.077762 rgb/1341848168.077762.png 1341848168.078289 depth/1341848168.078289.png
1341848168.113915 rgb/1341848168.113915.png 1341848168.113940 depth/1341848168.113940.png
1341848168.145814 rgb/1341848168.145814.png 1341848168.145831 depth/1341848168.145831.png
1341848168.178177 rgb/1341848168.178177.png 1341848168.178208 depth/1341848168.178208.png
1341848168.213862 rgb/1341848168.213862.png 1341848168.214329 depth/1341848168.214329.png
1341848168.245860 rgb/1341848168.245860.png 1341848168.245875 depth/1341848168.245875.png
1341848168.277845 rgb/1341848168.277845.png 1341848168.277853 depth/1341848168.277853.png
1341848168.313854 rgb/1341848168.313854.png 1341848168.313956 depth/1341848168.313956.png
1341848168.345794 rgb/1341848168.345794.png 1341848168.345813 depth/1341848168.345813.png
1341848168.381749 rgb/1341848168.381749.png 1341848168.381783 depth/1341848168.381783.png
1341848168.414476 rgb/1341848168.414476.png 1341848168.414932 depth/1341848168.414932.png
1341848168.446009 rgb/1341848168.446009.png 1341848168.446033 depth/1341848168.446033.png
1341848168.481915 rgb/1341848168.481915.png 1341848168.481937 depth/1341848168.481937.png
1341848168.513922 rgb/1341848168.513922.png 1341848168.513972 depth/1341848168.513972.png
1341848168.545964 rgb/1341848168.545964.png 1341848168.545981 depth/1341848168.545981.png
1341848168.613895 rgb/1341848168.613895.png 1341848168.613978 depth/1341848168.613978.png
1341848168.675019 rgb/1341848168.675019.png 1341848168.675050 depth/1341848168.675050.png
1341848168.707107 rgb/1341848168.707107.png 1341848168.707145 depth/1341848168.707145.png
1341848168.742926 rgb/1341848168.742926.png 1341848168.742939 depth/1341848168.742939.png
1341848168.774770 rgb/1341848168.774770.png 1341848168.774793 depth/1341848168.774793.png
1341848168.810809 rgb/1341848168.810809.png 1341848168.810840 depth/1341848168.810840.png
1341848168.842853 rgb/1341848168.842853.png 1341848168.842873 depth/1341848168.842873.png
1341848168.874791 rgb/1341848168.874791.png 1341848168.874805 depth/1341848168.874805.png
1341848168.910686 rgb/1341848168.910686.png 1341848168.910714 depth/1341848168.910714.png
1341848168.942836 rgb/1341848168.942836.png 1341848168.942845 depth/1341848168.942845.png
1341848168.974865 rgb/1341848168.974865.png 1341848168.975389 depth/1341848168.975389.png
1341848169.010900 rgb/1341848169.010900.png 1341848169.010938 depth/1341848169.010938.png
1341848169.042779 rgb/1341848169.042779.png 1341848169.042800 depth/1341848169.042800.png
1341848169.078862 rgb/1341848169.078862.png 1341848169.078889 depth/1341848169.078889.png
1341848169.110879 rgb/1341848169.110879.png 1341848169.111516 depth/1341848169.111516.png
1341848169.150210 rgb/1341848169.150210.png 1341848169.150244 depth/1341848169.150244.png
1341848169.210842 rgb/1341848169.210842.png 1341848169.210865 depth/1341848169.210865.png
1341848169.243106 rgb/1341848169.243106.png 1341848169.243783 depth/1341848169.243783.png
1341848169.278974 rgb/1341848169.278974.png 1341848169.279469 depth/1341848169.279469.png
1341848169.311325 rgb/1341848169.311325.png 1341848169.312085 depth/1341848169.312085.png
1341848169.346739 rgb/1341848169.346739.png 1341848169.346785 depth/1341848169.346785.png
1341848169.379283 rgb/1341848169.379283.png 1341848169.379341 depth/1341848169.379341.png
1341848169.411051 rgb/1341848169.411051.png 1341848169.411083 depth/1341848169.411083.png
1341848169.450797 rgb/1341848169.450797.png 1341848169.451304 depth/1341848169.451304.png
1341848169.487973 rgb/1341848169.487973.png 1341848169.488025 depth/1341848169.488025.png
1341848169.522430 rgb/1341848169.522430.png 1341848169.522459 depth/1341848169.522459.png
1341848169.550666 rgb/1341848169.550666.png 1341848169.550700 depth/1341848169.550700.png
1341848169.617846 rgb/1341848169.617846.png 1341848169.617906 depth/1341848169.617906.png
1341848169.678928 rgb/1341848169.678928.png 1341848169.678958 depth/1341848169.678958.png
1341848169.714725 rgb/1341848169.714725.png 1341848169.714739 depth/1341848169.714739.png
1341848169.747494 rgb/1341848169.747494.png 1341848169.747516 depth/1341848169.747516.png
1341848169.778997 rgb/1341848169.778997.png 1341848169.779523 depth/1341848169.779523.png
1341848169.814857 rgb/1341848169.814857.png 1341848169.814881 depth/1341848169.814881.png
1341848169.847459 rgb/1341848169.847459.png 1341848169.847481 depth/1341848169.847481.png
1341848169.882805 rgb/1341848169.882805.png 1341848169.882819 depth/1341848169.882819.png
1341848169.914790 rgb/1341848169.914790.png 1341848169.914802 depth/1341848169.914802.png
1341848169.946809 rgb/1341848169.946809.png 1341848169.946845 depth/1341848169.946845.png
1341848169.982763 rgb/1341848169.982763.png 1341848169.982786 depth/1341848169.982786.png
1341848170.014748 rgb/1341848170.014748.png 1341848170.014761 depth/1341848170.014761.png
1341848170.050791 rgb/1341848170.050791.png 1341848170.050817 depth/1341848170.050817.png
1341848170.082844 rgb/1341848170.082844.png 1341848170.082868 depth/1341848170.082868.png
1341848170.114925 rgb/1341848170.114925.png 1341848170.114939 depth/1341848170.114939.png
1341848170.150727 rgb/1341848170.150727.png 1341848170.150815 depth/1341848170.150815.png
1341848170.182802 rgb/1341848170.182802.png 1341848170.182815 depth/1341848170.182815.png
1341848170.214838 rgb/1341848170.214838.png 1341848170.214886 depth/1341848170.214886.png
1341848170.250748 rgb/1341848170.250748.png 1341848170.250785 depth/1341848170.250785.png
1341848170.282811 rgb/1341848170.282811.png 1341848170.282838 depth/1341848170.282838.png
1341848170.318864 rgb/1341848170.318864.png 1341848170.318891 depth/1341848170.318891.png
1341848170.350686 rgb/1341848170.350686.png 1341848170.350726 depth/1341848170.350726.png
1341848170.382951 rgb/1341848170.382951.png 1341848170.382971 depth/1341848170.382971.png
1341848170.419767 rgb/1341848170.419767.png 1341848170.419802 depth/1341848170.419802.png
1341848170.450820 rgb/1341848170.450820.png 1341848170.450855 depth/1341848170.450855.png
1341848170.482994 rgb/1341848170.482994.png 1341848170.483047 depth/1341848170.483047.png
1341848170.519221 rgb/1341848170.519221.png 1341848170.519264 depth/1341848170.519264.png
1341848170.550768 rgb/1341848170.550768.png 1341848170.550805 depth/1341848170.550805.png
1341848170.586877 rgb/1341848170.586877.png 1341848170.586901 depth/1341848170.586901.png
1341848170.618739 rgb/1341848170.618739.png 1341848170.619289 depth/1341848170.619289.png
1341848170.652332 rgb/1341848170.652332.png 1341848170.652359 depth/1341848170.652359.png
1341848170.686709 rgb/1341848170.686709.png 1341848170.686721 depth/1341848170.686721.png
1341848170.718864 rgb/1341848170.718864.png 1341848170.718890 depth/1341848170.718890.png
1341848170.750844 rgb/1341848170.750844.png 1341848170.751513 depth/1341848170.751513.png
1341848170.786698 rgb/1341848170.786698.png 1341848170.786710 depth/1341848170.786710.png
1341848170.818702 rgb/1341848170.818702.png 1341848170.818720 depth/1341848170.818720.png
1341848170.854826 rgb/1341848170.854826.png 1341848170.855230 depth/1341848170.855230.png
1341848170.886774 rgb/1341848170.886774.png 1341848170.887278 depth/1341848170.887278.png
1341848170.926076 rgb/1341848170.926076.png 1341848170.926108 depth/1341848170.926108.png
1341848170.958766 rgb/1341848170.958766.png 1341848170.958804 depth/1341848170.958804.png
1341848170.993725 rgb/1341848170.993725.png 1341848170.993740 depth/1341848170.993740.png
1341848171.025806 rgb/1341848171.025806.png 1341848171.025818 depth/1341848171.025818.png
1341848171.061925 rgb/1341848171.061925.png 1341848171.061939 depth/1341848171.061939.png
1341848171.093901 rgb/1341848171.093901.png 1341848171.093917 depth/1341848171.093917.png
1341848171.125860 rgb/1341848171.125860.png 1341848171.125918 depth/1341848171.125918.png
1341848171.161963 rgb/1341848171.161963.png 1341848171.161998 depth/1341848171.161998.png
1341848171.194020 rgb/1341848171.194020.png 1341848171.194090 depth/1341848171.194090.png
1341848171.262112 rgb/1341848171.262112.png 1341848171.262167 depth/1341848171.262167.png
1341848171.322894 rgb/1341848171.322894.png 1341848171.322905 depth/1341848171.322905.png
1341848171.354919 rgb/1341848171.354919.png 1341848171.354933 depth/1341848171.354933.png
1341848171.391228 rgb/1341848171.391228.png 1341848171.391255 depth/1341848171.391255.png
1341848171.422729 rgb/1341848171.422729.png 1341848171.422745 depth/1341848171.422745.png
1341848171.454760 rgb/1341848171.454760.png 1341848171.455244 depth/1341848171.455244.png
1341848171.490696 rgb/1341848171.490696.png 1341848171.490721 depth/1341848171.490721.png
1341848171.522921 rgb/1341848171.522921.png 1341848171.522974 depth/1341848171.522974.png
1341848171.558715 rgb/1341848171.558715.png 1341848171.558771 depth/1341848171.558771.png
1341848171.590717 rgb/1341848171.590717.png 1341848171.590751 depth/1341848171.590751.png
1341848171.622792 rgb/1341848171.622792.png 1341848171.622812 depth/1341848171.622812.png
1341848171.658850 rgb/1341848171.658850.png 1341848171.658878 depth/1341848171.658878.png
1341848171.690706 rgb/1341848171.690706.png 1341848171.690718 depth/1341848171.690718.png
1341848171.722808 rgb/1341848171.722808.png 1341848171.722842 depth/1341848171.722842.png
1341848171.758696 rgb/1341848171.758696.png 1341848171.758722 depth/1341848171.758722.png
1341848171.791064 rgb/1341848171.791064.png 1341848171.791086 depth/1341848171.791086.png
1341848171.826816 rgb/1341848171.826816.png 1341848171.826830 depth/1341848171.826830.png
1341848171.858914 rgb/1341848171.858914.png 1341848171.858926 depth/1341848171.858926.png
1341848171.890806 rgb/1341848171.890806.png 1341848171.890823 depth/1341848171.890823.png
1341848171.927081 rgb/1341848171.927081.png 1341848171.927110 depth/1341848171.927110.png
1341848171.958994 rgb/1341848171.958994.png 1341848171.959026 depth/1341848171.959026.png
1341848171.990766 rgb/1341848171.990766.png 1341848171.990798 depth/1341848171.990798.png
1341848172.026752 rgb/1341848172.026752.png 1341848172.026834 depth/1341848172.026834.png
1341848172.060568 rgb/1341848172.060568.png 1341848172.062128 depth/1341848172.062128.png
1341848172.094793 rgb/1341848172.094793.png 1341848172.094806 depth/1341848172.094806.png
1341848172.126919 rgb/1341848172.126919.png 1341848172.126959 depth/1341848172.126959.png
1341848172.158938 rgb/1341848172.158938.png 1341848172.159993 depth/1341848172.159993.png
1341848172.194741 rgb/1341848172.194741.png 1341848172.195427 depth/1341848172.195427.png
1341848172.226766 rgb/1341848172.226766.png 1341848172.226779 depth/1341848172.226779.png
1341848172.262925 rgb/1341848172.262925.png 1341848172.262952 depth/1341848172.262952.png
1341848172.295126 rgb/1341848172.295126.png 1341848172.295154 depth/1341848172.295154.png
1341848172.326863 rgb/1341848172.326863.png 1341848172.327491 depth/1341848172.327491.png
1341848172.362777 rgb/1341848172.362777.png 1341848172.362792 depth/1341848172.362792.png
1341848172.394860 rgb/1341848172.394860.png 1341848172.394923 depth/1341848172.394923.png
1341848172.426834 rgb/1341848172.426834.png 1341848172.426863 depth/1341848172.426863.png
1341848172.462869 rgb/1341848172.462869.png 1341848172.462879 depth/1341848172.462879.png
1341848172.501819 rgb/1341848172.501819.png 1341848172.501861 depth/1341848172.501861.png
1341848172.562940 rgb/1341848172.562940.png 1341848172.562960 depth/1341848172.562960.png
1341848172.601767 rgb/1341848172.601767.png 1341848172.601795 depth/1341848172.601795.png
1341848172.662791 rgb/1341848172.662791.png 1341848172.662846 depth/1341848172.662846.png
1341848172.694950 rgb/1341848172.694950.png 1341848172.694967 depth/1341848172.694967.png
1341848172.730726 rgb/1341848172.730726.png 1341848172.730772 depth/1341848172.730772.png
1341848172.762834 rgb/1341848172.762834.png 1341848172.762841 depth/1341848172.762841.png
1341848172.798891 rgb/1341848172.798891.png 1341848172.798923 depth/1341848172.798923.png
1341848172.830737 rgb/1341848172.830737.png 1341848172.830783 depth/1341848172.830783.png
1341848172.862925 rgb/1341848172.862925.png 1341848172.862949 depth/1341848172.862949.png
1341848172.898767 rgb/1341848172.898767.png 1341848172.898812 depth/1341848172.898812.png
1341848172.930849 rgb/1341848172.930849.png 1341848172.930866 depth/1341848172.930866.png
1341848172.970612 rgb/1341848172.970612.png 1341848172.974027 depth/1341848172.974027.png
1341848173.006783 rgb/1341848173.006783.png 1341848173.006794 depth/1341848173.006794.png
1341848173.037790 rgb/1341848173.037790.png 1341848173.037805 depth/1341848173.037805.png
1341848173.069723 rgb/1341848173.069723.png 1341848173.069732 depth/1341848173.069732.png
1341848173.105843 rgb/1341848173.105843.png 1341848173.105917 depth/1341848173.105917.png
1341848173.137826 rgb/1341848173.137826.png 1341848173.137836 depth/1341848173.137836.png
1341848173.173814 rgb/1341848173.173814.png 1341848173.173829 depth/1341848173.173829.png
1341848173.205862 rgb/1341848173.205862.png 1341848173.205878 depth/1341848173.205878.png
1341848173.237797 rgb/1341848173.237797.png 1341848173.237824 depth/1341848173.237824.png
1341848173.273875 rgb/1341848173.273875.png 1341848173.273885 depth/1341848173.273885.png
1341848173.305830 rgb/1341848173.305830.png 1341848173.305881 depth/1341848173.305881.png
1341848173.337822 rgb/1341848173.337822.png 1341848173.337842 depth/1341848173.337842.png
1341848173.373874 rgb/1341848173.373874.png 1341848173.373888 depth/1341848173.373888.png
1341848173.405797 rgb/1341848173.405797.png 1341848173.405856 depth/1341848173.405856.png
1341848173.437791 rgb/1341848173.437791.png 1341848173.437807 depth/1341848173.437807.png
1341848173.473910 rgb/1341848173.473910.png 1341848173.473933 depth/1341848173.473933.png
1341848173.505722 rgb/1341848173.505722.png 1341848173.505773 depth/1341848173.505773.png
1341848173.537755 rgb/1341848173.537755.png 1341848173.537771 depth/1341848173.537771.png
1341848173.574004 rgb/1341848173.574004.png 1341848173.574044 depth/1341848173.574044.png
1341848173.605758 rgb/1341848173.605758.png 1341848173.606489 depth/1341848173.606489.png
1341848173.641833 rgb/1341848173.641833.png 1341848173.641849 depth/1341848173.641849.png
1341848173.673821 rgb/1341848173.673821.png 1341848173.673845 depth/1341848173.673845.png
1341848173.705763 rgb/1341848173.705763.png 1341848173.705774 depth/1341848173.705774.png
1341848173.741896 rgb/1341848173.741896.png 1341848173.741920 depth/1341848173.741920.png
1341848173.774516 rgb/1341848173.774516.png 1341848173.774529 depth/1341848173.774529.png
1341848173.805808 rgb/1341848173.805808.png 1341848173.805825 depth/1341848173.805825.png
1341848173.841832 rgb/1341848173.841832.png 1341848173.841854 depth/1341848173.841854.png
1341848173.905937 rgb/1341848173.905937.png 1341848173.905985 depth/1341848173.905985.png
1341848173.973935 rgb/1341848173.973935.png 1341848173.973963 depth/1341848173.973963.png
1341848174.010026 rgb/1341848174.010026.png 1341848174.010041 depth/1341848174.010041.png
1341848174.041752 rgb/1341848174.041752.png 1341848174.041770 depth/1341848174.041770.png
1341848174.073840 rgb/1341848174.073840.png 1341848174.073851 depth/1341848174.073851.png
1341848174.109741 rgb/1341848174.109741.png 1341848174.109758 depth/1341848174.109758.png
1341848174.170884 rgb/1341848174.170884.png 1341848174.170916 depth/1341848174.170916.png
1341848174.202769 rgb/1341848174.202769.png 1341848174.202843 depth/1341848174.202843.png
1341848174.238812 rgb/1341848174.238812.png 1341848174.238828 depth/1341848174.238828.png
1341848174.270774 rgb/1341848174.270774.png 1341848174.270802 depth/1341848174.270802.png
1341848174.306847 rgb/1341848174.306847.png 1341848174.306867 depth/1341848174.306867.png
1341848174.338829 rgb/1341848174.338829.png 1341848174.338901 depth/1341848174.338901.png
1341848174.370884 rgb/1341848174.370884.png 1341848174.370901 depth/1341848174.370901.png
1341848174.406831 rgb/1341848174.406831.png 1341848174.406853 depth/1341848174.406853.png
1341848174.438954 rgb/1341848174.438954.png 1341848174.438983 depth/1341848174.438983.png
1341848174.474871 rgb/1341848174.474871.png 1341848174.474886 depth/1341848174.474886.png
1341848174.506796 rgb/1341848174.506796.png 1341848174.506814 depth/1341848174.506814.png
1341848174.538782 rgb/1341848174.538782.png 1341848174.539351 depth/1341848174.539351.png
1341848174.574817 rgb/1341848174.574817.png 1341848174.574879 depth/1341848174.574879.png
1341848174.606806 rgb/1341848174.606806.png 1341848174.606825 depth/1341848174.606825.png
1341848174.638715 rgb/1341848174.638715.png 1341848174.638728 depth/1341848174.638728.png
1341848174.674952 rgb/1341848174.674952.png 1341848174.674965 depth/1341848174.674965.png
1341848174.706853 rgb/1341848174.706853.png 1341848174.706871 depth/1341848174.706871.png
1341848174.742828 rgb/1341848174.742828.png 1341848174.743451 depth/1341848174.743451.png
1341848174.774773 rgb/1341848174.774773.png 1341848174.774785 depth/1341848174.774785.png
1341848174.807941 rgb/1341848174.807941.png 1341848174.807964 depth/1341848174.807964.png
1341848174.842786 rgb/1341848174.842786.png 1341848174.842803 depth/1341848174.842803.png
1341848174.874849 rgb/1341848174.874849.png 1341848174.874862 depth/1341848174.874862.png
1341848174.906906 rgb/1341848174.906906.png 1341848174.906926 depth/1341848174.906926.png
1341848174.942723 rgb/1341848174.942723.png 1341848174.942734 depth/1341848174.942734.png
1341848174.974809 rgb/1341848174.974809.png 1341848174.974827 depth/1341848174.974827.png
1341848175.010859 rgb/1341848175.010859.png 1341848175.010878 depth/1341848175.010878.png
1341848175.042878 rgb/1341848175.042878.png 1341848175.042895 depth/1341848175.042895.png
1341848175.074872 rgb/1341848175.074872.png 1341848175.075207 depth/1341848175.075207.png
1341848175.110772 rgb/1341848175.110772.png 1341848175.111132 depth/1341848175.111132.png
1341848175.142771 rgb/1341848175.142771.png 1341848175.142784 depth/1341848175.142784.png
1341848175.174790 rgb/1341848175.174790.png 1341848175.174803 depth/1341848175.174803.png
1341848175.210897 rgb/1341848175.210897.png 1341848175.210924 depth/1341848175.210924.png
1341848175.242842 rgb/1341848175.242842.png 1341848175.242865 depth/1341848175.242865.png
1341848175.278894 rgb/1341848175.278894.png 1341848175.278919 depth/1341848175.278919.png
1341848175.310838 rgb/1341848175.310838.png 1341848175.310868 depth/1341848175.310868.png
1341848175.342894 rgb/1341848175.342894.png 1341848175.343671 depth/1341848175.343671.png
1341848175.378878 rgb/1341848175.378878.png 1341848175.378899 depth/1341848175.378899.png
1341848175.410874 rgb/1341848175.410874.png 1341848175.410890 depth/1341848175.410890.png
1341848175.449968 rgb/1341848175.449968.png 1341848175.446776 depth/1341848175.446776.png
1341848175.478737 rgb/1341848175.478737.png 1341848175.478756 depth/1341848175.478756.png
1341848175.510715 rgb/1341848175.510715.png 1341848175.510725 depth/1341848175.510725.png
1341848175.546859 rgb/1341848175.546859.png 1341848175.546886 depth/1341848175.546886.png
1341848175.578794 rgb/1341848175.578794.png 1341848175.579431 depth/1341848175.579431.png
1341848175.611161 rgb/1341848175.611161.png 1341848175.611177 depth/1341848175.611177.png
1341848175.646795 rgb/1341848175.646795.png 1341848175.646807 depth/1341848175.646807.png
1341848175.678819 rgb/1341848175.678819.png 1341848175.678834 depth/1341848175.678834.png
1341848175.714827 rgb/1341848175.714827.png 1341848175.714839 depth/1341848175.714839.png
1341848175.746817 rgb/1341848175.746817.png 1341848175.746834 depth/1341848175.746834.png
1341848175.779170 rgb/1341848175.779170.png 1341848175.779186 depth/1341848175.779186.png
1341848175.814826 rgb/1341848175.814826.png 1341848175.814837 depth/1341848175.814837.png
1341848175.846890 rgb/1341848175.846890.png 1341848175.846900 depth/1341848175.846900.png
1341848175.878860 rgb/1341848175.878860.png 1341848175.878878 depth/1341848175.878878.png
1341848175.914756 rgb/1341848175.914756.png 1341848175.914780 depth/1341848175.914780.png
1341848175.946759 rgb/1341848175.946759.png 1341848175.946770 depth/1341848175.946770.png
1341848175.982955 rgb/1341848175.982955.png 1341848175.982973 depth/1341848175.982973.png
1341848176.015034 rgb/1341848176.015034.png 1341848176.015763 depth/1341848176.015763.png
1341848176.047105 rgb/1341848176.047105.png 1341848176.047149 depth/1341848176.047149.png
1341848176.082733 rgb/1341848176.082733.png 1341848176.082752 depth/1341848176.082752.png
1341848176.114748 rgb/1341848176.114748.png 1341848176.114764 depth/1341848176.114764.png
1341848176.146780 rgb/1341848176.146780.png 1341848176.146797 depth/1341848176.146797.png
1341848176.182775 rgb/1341848176.182775.png 1341848176.182786 depth/1341848176.182786.png
1341848176.214889 rgb/1341848176.214889.png 1341848176.214908 depth/1341848176.214908.png
1341848176.250825 rgb/1341848176.250825.png 1341848176.250834 depth/1341848176.250834.png
1341848176.282957 rgb/1341848176.282957.png 1341848176.282983 depth/1341848176.282983.png
1341848176.314841 rgb/1341848176.314841.png 1341848176.314859 depth/1341848176.314859.png
1341848176.350889 rgb/1341848176.350889.png 1341848176.350904 depth/1341848176.350904.png
1341848176.382837 rgb/1341848176.382837.png 1341848176.382963 depth/1341848176.382963.png
1341848176.415025 rgb/1341848176.415025.png 1341848176.415107 depth/1341848176.415107.png
1341848176.450729 rgb/1341848176.450729.png 1341848176.450748 depth/1341848176.450748.png
1341848176.482879 rgb/1341848176.482879.png 1341848176.482900 depth/1341848176.482900.png
1341848176.521896 rgb/1341848176.521896.png 1341848176.521946 depth/1341848176.521946.png
1341848176.583070 rgb/1341848176.583070.png 1341848176.583106 depth/1341848176.583106.png
1341848176.618907 rgb/1341848176.618907.png 1341848176.619756 depth/1341848176.619756.png
1341848176.651190 rgb/1341848176.651190.png 1341848176.652036 depth/1341848176.652036.png
1341848176.686920 rgb/1341848176.686920.png 1341848176.686941 depth/1341848176.686941.png
1341848176.718767 rgb/1341848176.718767.png 1341848176.718779 depth/1341848176.718779.png
1341848176.750796 rgb/1341848176.750796.png 1341848176.750813 depth/1341848176.750813.png
1341848176.786859 rgb/1341848176.786859.png 1341848176.786870 depth/1341848176.786870.png
1341848176.818866 rgb/1341848176.818866.png 1341848176.818917 depth/1341848176.818917.png
1341848176.851038 rgb/1341848176.851038.png 1341848176.851082 depth/1341848176.851082.png
1341848176.886870 rgb/1341848176.886870.png 1341848176.886884 depth/1341848176.886884.png
1341848176.918895 rgb/1341848176.918895.png 1341848176.918921 depth/1341848176.918921.png
1341848176.954856 rgb/1341848176.954856.png 1341848176.954873 depth/1341848176.954873.png
1341848176.987277 rgb/1341848176.987277.png 1341848176.987352 depth/1341848176.987352.png
1341848177.054822 rgb/1341848177.054822.png 1341848177.054842 depth/1341848177.054842.png
1341848177.094476 rgb/1341848177.094476.png 1341848177.094839 depth/1341848177.094839.png
1341848177.157761 rgb/1341848177.157761.png 1341848177.157788 depth/1341848177.157788.png
1341848177.194043 rgb/1341848177.194043.png 1341848177.194120 depth/1341848177.194120.png
1341848177.225636 rgb/1341848177.225636.png 1341848177.225645 depth/1341848177.225645.png
1341848177.258090 rgb/1341848177.258090.png 1341848177.258111 depth/1341848177.258111.png
1341848177.293736 rgb/1341848177.293736.png 1341848177.293747 depth/1341848177.293747.png
1341848177.326084 rgb/1341848177.326084.png 1341848177.326099 depth/1341848177.326099.png
1341848177.361835 rgb/1341848177.361835.png 1341848177.361866 depth/1341848177.361866.png
1341848177.393840 rgb/1341848177.393840.png 1341848177.393857 depth/1341848177.393857.png
1341848177.425820 rgb/1341848177.425820.png 1341848177.425830 depth/1341848177.425830.png
1341848177.462295 rgb/1341848177.462295.png 1341848177.462332 depth/1341848177.462332.png
1341848177.493752 rgb/1341848177.493752.png 1341848177.494289 depth/1341848177.494289.png
1341848177.529808 rgb/1341848177.529808.png 1341848177.529824 depth/1341848177.529824.png
1341848177.561835 rgb/1341848177.561835.png 1341848177.562845 depth/1341848177.562845.png
1341848177.594019 rgb/1341848177.594019.png 1341848177.594043 depth/1341848177.594043.png
1341848177.629925 rgb/1341848177.629925.png 1341848177.630007 depth/1341848177.630007.png
1341848177.661760 rgb/1341848177.661760.png 1341848177.661773 depth/1341848177.661773.png
1341848177.697943 rgb/1341848177.697943.png 1341848177.697984 depth/1341848177.697984.png
1341848177.729811 rgb/1341848177.729811.png 1341848177.729831 depth/1341848177.729831.png
1341848177.761783 rgb/1341848177.761783.png 1341848177.761803 depth/1341848177.761803.png
1341848177.797765 rgb/1341848177.797765.png 1341848177.797807 depth/1341848177.797807.png
1341848177.829738 rgb/1341848177.829738.png 1341848177.829783 depth/1341848177.829783.png
1341848177.861768 rgb/1341848177.861768.png 1341848177.861786 depth/1341848177.861786.png
1341848177.897747 rgb/1341848177.897747.png 1341848177.897755 depth/1341848177.897755.png
1341848177.929810 rgb/1341848177.929810.png 1341848177.929832 depth/1341848177.929832.png
1341848177.965798 rgb/1341848177.965798.png 1341848177.965816 depth/1341848177.965816.png
1341848178.029804 rgb/1341848178.029804.png 1341848178.029836 depth/1341848178.029836.png
1341848178.090881 rgb/1341848178.090881.png 1341848178.090922 depth/1341848178.090922.png
1341848178.126734 rgb/1341848178.126734.png 1341848178.126771 depth/1341848178.126771.png
1341848178.158813 rgb/1341848178.158813.png 1341848178.158840 depth/1341848178.158840.png
1341848178.195070 rgb/1341848178.195070.png 1341848178.195585 depth/1341848178.195585.png
1341848178.226831 rgb/1341848178.226831.png 1341848178.226920 depth/1341848178.226920.png
1341848178.258943 rgb/1341848178.258943.png 1341848178.259006 depth/1341848178.259006.png
1341848178.294902 rgb/1341848178.294902.png 1341848178.294920 depth/1341848178.294920.png
1341848178.326775 rgb/1341848178.326775.png 1341848178.326793 depth/1341848178.326793.png
1341848178.358885 rgb/1341848178.358885.png 1341848178.358906 depth/1341848178.358906.png
1341848178.395033 rgb/1341848178.395033.png 1341848178.395058 depth/1341848178.395058.png
1341848178.426921 rgb/1341848178.426921.png 1341848178.427372 depth/1341848178.427372.png
1341848178.462917 rgb/1341848178.462917.png 1341848178.462941 depth/1341848178.462941.png
1341848178.526764 rgb/1341848178.526764.png 1341848178.526826 depth/1341848178.526826.png
1341848178.562821 rgb/1341848178.562821.png 1341848178.562840 depth/1341848178.562840.png
1341848178.595066 rgb/1341848178.595066.png 1341848178.595111 depth/1341848178.595111.png
1341848178.626774 rgb/1341848178.626774.png 1341848178.626797 depth/1341848178.626797.png
1341848178.662858 rgb/1341848178.662858.png 1341848178.662879 depth/1341848178.662879.png
1341848178.695067 rgb/1341848178.695067.png 1341848178.695107 depth/1341848178.695107.png
1341848178.730758 rgb/1341848178.730758.png 1341848178.730797 depth/1341848178.730797.png
1341848178.762794 rgb/1341848178.762794.png 1341848178.762823 depth/1341848178.762823.png
1341848178.795407 rgb/1341848178.795407.png 1341848178.795423 depth/1341848178.795423.png
1341848178.830977 rgb/1341848178.830977.png 1341848178.830997 depth/1341848178.830997.png
1341848178.862784 rgb/1341848178.862784.png 1341848178.862813 depth/1341848178.862813.png
1341848178.899392 rgb/1341848178.899392.png 1341848178.900146 depth/1341848178.900146.png
1341848178.930784 rgb/1341848178.930784.png 1341848178.930812 depth/1341848178.930812.png
1341848178.962815 rgb/1341848178.962815.png 1341848178.962827 depth/1341848178.962827.png
1341848178.998815 rgb/1341848178.998815.png 1341848178.998826 depth/1341848178.998826.png
1341848179.030730 rgb/1341848179.030730.png 1341848179.030755 depth/1341848179.030755.png
1341848179.064390 rgb/1341848179.064390.png 1341848179.065275 depth/1341848179.065275.png
1341848179.098853 rgb/1341848179.098853.png 1341848179.098868 depth/1341848179.098868.png
1341848179.130927 rgb/1341848179.130927.png 1341848179.130975 depth/1341848179.130975.png
1341848179.167572 rgb/1341848179.167572.png 1341848179.167818 depth/1341848179.167818.png
1341848179.198708 rgb/1341848179.198708.png 1341848179.198747 depth/1341848179.198747.png
1341848179.230752 rgb/1341848179.230752.png 1341848179.230786 depth/1341848179.230786.png
1341848179.266826 rgb/1341848179.266826.png 1341848179.266847 depth/1341848179.266847.png
1341848179.298787 rgb/1341848179.298787.png 1341848179.298806 depth/1341848179.298806.png
1341848179.331143 rgb/1341848179.331143.png 1341848179.331158 depth/1341848179.331158.png
1341848179.367016 rgb/1341848179.367016.png 1341848179.367031 depth/1341848179.367031.png
1341848179.398829 rgb/1341848179.398829.png 1341848179.398844 depth/1341848179.398844.png
1341848179.434934 rgb/1341848179.434934.png 1341848179.434965 depth/1341848179.434965.png
1341848179.466734 rgb/1341848179.466734.png 1341848179.466761 depth/1341848179.466761.png
1341848179.498792 rgb/1341848179.498792.png 1341848179.498808 depth/1341848179.498808.png
1341848179.534788 rgb/1341848179.534788.png 1341848179.534801 depth/1341848179.534801.png
1341848179.566960 rgb/1341848179.566960.png 1341848179.566984 depth/1341848179.566984.png
1341848179.598799 rgb/1341848179.598799.png 1341848179.601665 depth/1341848179.601665.png
1341848179.634855 rgb/1341848179.634855.png 1341848179.635461 depth/1341848179.635461.png
1341848179.702905 rgb/1341848179.702905.png 1341848179.702941 depth/1341848179.702941.png
1341848179.735219 rgb/1341848179.735219.png 1341848179.735241 depth/1341848179.735241.png
1341848179.766770 rgb/1341848179.766770.png 1341848179.766822 depth/1341848179.766822.png
1341848179.805774 rgb/1341848179.805774.png 1341848179.805806 depth/1341848179.805806.png
1341848179.870728 rgb/1341848179.870728.png 1341848179.870743 depth/1341848179.870743.png
1341848179.902869 rgb/1341848179.902869.png 1341848179.902896 depth/1341848179.902896.png
1341848179.935830 rgb/1341848179.935830.png 1341848179.936387 depth/1341848179.936387.png
1341848179.970791 rgb/1341848179.970791.png 1341848179.971251 depth/1341848179.971251.png
1341848180.002880 rgb/1341848180.002880.png 1341848180.002913 depth/1341848180.002913.png
1341848180.034824 rgb/1341848180.034824.png 1341848180.034851 depth/1341848180.034851.png
1341848180.070686 rgb/1341848180.070686.png 1341848180.070705 depth/1341848180.070705.png
1341848180.102836 rgb/1341848180.102836.png 1341848180.102897 depth/1341848180.102897.png
1341848180.138878 rgb/1341848180.138878.png 1341848180.138923 depth/1341848180.138923.png
1341848180.170934 rgb/1341848180.170934.png 1341848180.170958 depth/1341848180.170958.png
1341848180.203156 rgb/1341848180.203156.png 1341848180.203173 depth/1341848180.203173.png
1341848180.238904 rgb/1341848180.238904.png 1341848180.238932 depth/1341848180.238932.png
1341848180.270806 rgb/1341848180.270806.png 1341848180.270859 depth/1341848180.270859.png
1341848180.302804 rgb/1341848180.302804.png 1341848180.302834 depth/1341848180.302834.png
1341848180.338783 rgb/1341848180.338783.png 1341848180.338798 depth/1341848180.338798.png
1341848180.370733 rgb/1341848180.370733.png 1341848180.370749 depth/1341848180.370749.png
1341848180.406759 rgb/1341848180.406759.png 1341848180.406817 depth/1341848180.406817.png
1341848180.438828 rgb/1341848180.438828.png 1341848180.438862 depth/1341848180.438862.png
1341848180.470759 rgb/1341848180.470759.png 1341848180.470812 depth/1341848180.470812.png
1341848180.506785 rgb/1341848180.506785.png 1341848180.506824 depth/1341848180.506824.png
1341848180.538868 rgb/1341848180.538868.png 1341848180.538879 depth/1341848180.538879.png
1341848180.570762 rgb/1341848180.570762.png 1341848180.570817 depth/1341848180.570817.png
1341848180.606747 rgb/1341848180.606747.png 1341848180.606765 depth/1341848180.606765.png
1341848180.638758 rgb/1341848180.638758.png 1341848180.638772 depth/1341848180.638772.png
1341848180.674895 rgb/1341848180.674895.png 1341848180.674930 depth/1341848180.674930.png
1341848180.706981 rgb/1341848180.706981.png 1341848180.707347 depth/1341848180.707347.png
1341848180.738932 rgb/1341848180.738932.png 1341848180.738964 depth/1341848180.738964.png
1341848180.774902 rgb/1341848180.774902.png 1341848180.774935 depth/1341848180.774935.png
1341848180.806828 rgb/1341848180.806828.png 1341848180.806863 depth/1341848180.806863.png
1341848180.838956 rgb/1341848180.838956.png 1341848180.839004 depth/1341848180.839004.png
1341848180.874944 rgb/1341848180.874944.png 1341848180.874955 depth/1341848180.874955.png
1341848180.906881 rgb/1341848180.906881.png 1341848180.907666 depth/1341848180.907666.png
1341848180.942728 rgb/1341848180.942728.png 1341848180.942739 depth/1341848180.942739.png
1341848180.974713 rgb/1341848180.974713.png 1341848180.974728 depth/1341848180.974728.png
1341848181.007092 rgb/1341848181.007092.png 1341848181.007128 depth/1341848181.007128.png
1341848181.042848 rgb/1341848181.042848.png 1341848181.042961 depth/1341848181.042961.png
1341848181.074804 rgb/1341848181.074804.png 1341848181.074814 depth/1341848181.074814.png
1341848181.110856 rgb/1341848181.110856.png 1341848181.110886 depth/1341848181.110886.png
1341848181.142864 rgb/1341848181.142864.png 1341848181.142881 depth/1341848181.142881.png
1341848181.174755 rgb/1341848181.174755.png 1341848181.174776 depth/1341848181.174776.png
1341848181.210765 rgb/1341848181.210765.png 1341848181.210779 depth/1341848181.210779.png
1341848181.242738 rgb/1341848181.242738.png 1341848181.242754 depth/1341848181.242754.png
1341848181.274868 rgb/1341848181.274868.png 1341848181.274896 depth/1341848181.274896.png
1341848181.310763 rgb/1341848181.310763.png 1341848181.310795 depth/1341848181.310795.png
1341848181.342827 rgb/1341848181.342827.png 1341848181.342856 depth/1341848181.342856.png
1341848181.378837 rgb/1341848181.378837.png 1341848181.378871 depth/1341848181.378871.png
1341848181.410740 rgb/1341848181.410740.png 1341848181.410827 depth/1341848181.410827.png
1341848181.442829 rgb/1341848181.442829.png 1341848181.442843 depth/1341848181.442843.png
1341848181.478731 rgb/1341848181.478731.png 1341848181.478744 depth/1341848181.478744.png
1341848181.510949 rgb/1341848181.510949.png 1341848181.510966 depth/1341848181.510966.png
1341848181.542963 rgb/1341848181.542963.png 1341848181.543009 depth/1341848181.543009.png
1341848181.578959 rgb/1341848181.578959.png 1341848181.578973 depth/1341848181.578973.png
1341848181.610749 rgb/1341848181.610749.png 1341848181.610769 depth/1341848181.610769.png
1341848181.646934 rgb/1341848181.646934.png 1341848181.646964 depth/1341848181.646964.png
1341848181.678877 rgb/1341848181.678877.png 1341848181.678905 depth/1341848181.678905.png
1341848181.710813 rgb/1341848181.710813.png 1341848181.710844 depth/1341848181.710844.png
1341848181.746808 rgb/1341848181.746808.png 1341848181.746866 depth/1341848181.746866.png
1341848181.779006 rgb/1341848181.779006.png 1341848181.779041 depth/1341848181.779041.png
1341848181.810899 rgb/1341848181.810899.png 1341848181.810953 depth/1341848181.810953.png
1341848181.846767 rgb/1341848181.846767.png 1341848181.846809 depth/1341848181.846809.png
1341848181.878878 rgb/1341848181.878878.png 1341848181.878894 depth/1341848181.878894.png
1341848181.914973 rgb/1341848181.914973.png 1341848181.914986 depth/1341848181.914986.png
1341848181.946830 rgb/1341848181.946830.png 1341848181.946856 depth/1341848181.946856.png
1341848181.978846 rgb/1341848181.978846.png 1341848181.978870 depth/1341848181.978870.png
1341848182.014736 rgb/1341848182.014736.png 1341848182.014780 depth/1341848182.014780.png
1341848182.046732 rgb/1341848182.046732.png 1341848182.046758 depth/1341848182.046758.png
1341848182.082918 rgb/1341848182.082918.png 1341848182.082952 depth/1341848182.082952.png
1341848182.114795 rgb/1341848182.114795.png 1341848182.114826 depth/1341848182.114826.png
1341848182.146819 rgb/1341848182.146819.png 1341848182.146833 depth/1341848182.146833.png
1341848182.182814 rgb/1341848182.182814.png 1341848182.182850 depth/1341848182.182850.png
1341848182.219905 rgb/1341848182.219905.png 1341848182.219927 depth/1341848182.219927.png
1341848182.253742 rgb/1341848182.253742.png 1341848182.254256 depth/1341848182.254256.png
1341848182.285827 rgb/1341848182.285827.png 1341848182.285873 depth/1341848182.285873.png
1341848182.321829 rgb/1341848182.321829.png 1341848182.321861 depth/1341848182.321861.png
1341848182.353834 rgb/1341848182.353834.png 1341848182.353865 depth/1341848182.353865.png
1341848182.385924 rgb/1341848182.385924.png 1341848182.386428 depth/1341848182.386428.png
1341848182.421864 rgb/1341848182.421864.png 1341848182.421884 depth/1341848182.421884.png
1341848182.453954 rgb/1341848182.453954.png 1341848182.454005 depth/1341848182.454005.png
1341848182.489903 rgb/1341848182.489903.png 1341848182.489920 depth/1341848182.489920.png
1341848182.521964 rgb/1341848182.521964.png 1341848182.521992 depth/1341848182.521992.png
1341848182.553838 rgb/1341848182.553838.png 1341848182.553856 depth/1341848182.553856.png
1341848182.589858 rgb/1341848182.589858.png 1341848182.589904 depth/1341848182.589904.png
1341848182.621851 rgb/1341848182.621851.png 1341848182.621868 depth/1341848182.621868.png
1341848182.657889 rgb/1341848182.657889.png 1341848182.658010 depth/1341848182.658010.png
1341848182.689839 rgb/1341848182.689839.png 1341848182.691406 depth/1341848182.691406.png
1341848182.725864 rgb/1341848182.725864.png 1341848182.725884 depth/1341848182.725884.png
1341848182.757767 rgb/1341848182.757767.png 1341848182.757803 depth/1341848182.757803.png
1341848182.789815 rgb/1341848182.789815.png 1341848182.789828 depth/1341848182.789828.png
1341848182.825890 rgb/1341848182.825890.png 1341848182.825943 depth/1341848182.825943.png
1341848182.857788 rgb/1341848182.857788.png 1341848182.857833 depth/1341848182.857833.png
1341848182.893805 rgb/1341848182.893805.png 1341848182.893821 depth/1341848182.893821.png
1341848182.925798 rgb/1341848182.925798.png 1341848182.925826 depth/1341848182.925826.png
1341848182.957794 rgb/1341848182.957794.png 1341848182.957834 depth/1341848182.957834.png
1341848182.993756 rgb/1341848182.993756.png 1341848182.993785 depth/1341848182.993785.png
1341848183.025772 rgb/1341848183.025772.png 1341848183.025797 depth/1341848183.025797.png
1341848183.061899 rgb/1341848183.061899.png 1341848183.061930 depth/1341848183.061930.png
1341848183.093803 rgb/1341848183.093803.png 1341848183.093830 depth/1341848183.093830.png
1341848183.125814 rgb/1341848183.125814.png 1341848183.125829 depth/1341848183.125829.png
1341848183.162482 rgb/1341848183.162482.png 1341848183.162947 depth/1341848183.162947.png
1341848183.193834 rgb/1341848183.193834.png 1341848183.193846 depth/1341848183.193846.png
1341848183.225770 rgb/1341848183.225770.png 1341848183.225792 depth/1341848183.225792.png
1341848183.262162 rgb/1341848183.262162.png 1341848183.262176 depth/1341848183.262176.png
1341848183.293872 rgb/1341848183.293872.png 1341848183.293896 depth/1341848183.293896.png
1341848183.329801 rgb/1341848183.329801.png 1341848183.329817 depth/1341848183.329817.png
1341848183.361720 rgb/1341848183.361720.png 1341848183.361746 depth/1341848183.361746.png
1341848183.394404 rgb/1341848183.394404.png 1341848183.394423 depth/1341848183.394423.png
1341848183.429837 rgb/1341848183.429837.png 1341848183.429857 depth/1341848183.429857.png
1341848183.461970 rgb/1341848183.461970.png 1341848183.461987 depth/1341848183.461987.png
1341848183.493746 rgb/1341848183.493746.png 1341848183.493761 depth/1341848183.493761.png
1341848183.529876 rgb/1341848183.529876.png 1341848183.530223 depth/1341848183.530223.png
1341848183.562076 rgb/1341848183.562076.png 1341848183.562091 depth/1341848183.562091.png
1341848183.593743 rgb/1341848183.593743.png 1341848183.593780 depth/1341848183.593780.png
1341848183.629850 rgb/1341848183.629850.png 1341848183.629872 depth/1341848183.629872.png
1341848183.661787 rgb/1341848183.661787.png 1341848183.662297 depth/1341848183.662297.png
1341848183.693769 rgb/1341848183.693769.png 1341848183.693785 depth/1341848183.693785.png
1341848183.729824 rgb/1341848183.729824.png 1341848183.729856 depth/1341848183.729856.png
1341848183.762162 rgb/1341848183.762162.png 1341848183.762178 depth/1341848183.762178.png
1341848183.793834 rgb/1341848183.793834.png 1341848183.793860 depth/1341848183.793860.png
1341848183.829855 rgb/1341848183.829855.png 1341848183.829873 depth/1341848183.829873.png
1341848183.861799 rgb/1341848183.861799.png 1341848183.861813 depth/1341848183.861813.png
1341848183.929834 rgb/1341848183.929834.png 1341848183.929878 depth/1341848183.929878.png
1341848183.990807 rgb/1341848183.990807.png 1341848183.990837 depth/1341848183.990837.png
1341848184.022837 rgb/1341848184.022837.png 1341848184.023273 depth/1341848184.023273.png
1341848184.058822 rgb/1341848184.058822.png 1341848184.058835 depth/1341848184.058835.png
1341848184.090822 rgb/1341848184.090822.png 1341848184.090837 depth/1341848184.090837.png
1341848184.126918 rgb/1341848184.126918.png 1341848184.126932 depth/1341848184.126932.png
1341848184.158763 rgb/1341848184.158763.png 1341848184.158779 depth/1341848184.158779.png
1341848184.190683 rgb/1341848184.190683.png 1341848184.190724 depth/1341848184.190724.png
1341848184.226995 rgb/1341848184.226995.png 1341848184.227736 depth/1341848184.227736.png
1341848184.258717 rgb/1341848184.258717.png 1341848184.258749 depth/1341848184.258749.png
1341848184.294799 rgb/1341848184.294799.png 1341848184.294819 depth/1341848184.294819.png
1341848184.326946 rgb/1341848184.326946.png 1341848184.326963 depth/1341848184.326963.png
1341848184.358773 rgb/1341848184.358773.png 1341848184.358812 depth/1341848184.358812.png
1341848184.394778 rgb/1341848184.394778.png 1341848184.394838 depth/1341848184.394838.png
1341848184.427508 rgb/1341848184.427508.png 1341848184.428198 depth/1341848184.428198.png
1341848184.458905 rgb/1341848184.458905.png 1341848184.459540 depth/1341848184.459540.png
1341848184.494708 rgb/1341848184.494708.png 1341848184.494786 depth/1341848184.494786.png
1341848184.526912 rgb/1341848184.526912.png 1341848184.527697 depth/1341848184.527697.png
1341848184.562959 rgb/1341848184.562959.png 1341848184.563970 depth/1341848184.563970.png
1341848184.596096 rgb/1341848184.596096.png 1341848184.597267 depth/1341848184.597267.png
1341848184.663064 rgb/1341848184.663064.png 1341848184.664142 depth/1341848184.664142.png
1341848184.695880 rgb/1341848184.695880.png 1341848184.701018 depth/1341848184.701018.png
1341848184.727939 rgb/1341848184.727939.png 1341848184.728039 depth/1341848184.728039.png
1341848184.763244 rgb/1341848184.763244.png 1341848184.763959 depth/1341848184.763959.png
1341848184.831507 rgb/1341848184.831507.png 1341848184.833694 depth/1341848184.833694.png
1341848184.894875 rgb/1341848184.894875.png 1341848184.894917 depth/1341848184.894917.png
1341848184.931622 rgb/1341848184.931622.png 1341848184.931964 depth/1341848184.931964.png
1341848184.962954 rgb/1341848184.962954.png 1341848184.963561 depth/1341848184.963561.png
1341848184.995053 rgb/1341848184.995053.png 1341848184.995070 depth/1341848184.995070.png
1341848185.031178 rgb/1341848185.031178.png 1341848185.032961 depth/1341848185.032961.png
1341848185.063733 rgb/1341848185.063733.png 1341848185.064771 depth/1341848185.064771.png
1341848185.099890 rgb/1341848185.099890.png 1341848185.100246 depth/1341848185.100246.png
1341848185.135017 rgb/1341848185.135017.png 1341848185.136756 depth/1341848185.136756.png
1341848185.163331 rgb/1341848185.163331.png 1341848185.163748 depth/1341848185.163748.png
1341848185.199006 rgb/1341848185.199006.png 1341848185.200133 depth/1341848185.200133.png
1341848185.231103 rgb/1341848185.231103.png 1341848185.231712 depth/1341848185.231712.png
1341848185.263016 rgb/1341848185.263016.png 1341848185.263032 depth/1341848185.263032.png
1341848185.298750 rgb/1341848185.298750.png 1341848185.298770 depth/1341848185.298770.png
1341848185.330829 rgb/1341848185.330829.png 1341848185.330848 depth/1341848185.330848.png
1341848185.366729 rgb/1341848185.366729.png 1341848185.366741 depth/1341848185.366741.png
1341848185.398889 rgb/1341848185.398889.png 1341848185.398930 depth/1341848185.398930.png
1341848185.430753 rgb/1341848185.430753.png 1341848185.430798 depth/1341848185.430798.png
1341848185.466829 rgb/1341848185.466829.png 1341848185.466843 depth/1341848185.466843.png
1341848185.498828 rgb/1341848185.498828.png 1341848185.498841 depth/1341848185.498841.png
1341848185.534866 rgb/1341848185.534866.png 1341848185.535063 depth/1341848185.535063.png
1341848185.566779 rgb/1341848185.566779.png 1341848185.566793 depth/1341848185.566793.png
1341848185.598979 rgb/1341848185.598979.png 1341848185.598996 depth/1341848185.598996.png
1341848185.634809 rgb/1341848185.634809.png 1341848185.634891 depth/1341848185.634891.png
1341848185.698977 rgb/1341848185.698977.png 1341848185.699032 depth/1341848185.699032.png
1341848185.734944 rgb/1341848185.734944.png 1341848185.734961 depth/1341848185.734961.png
1341848185.766700 rgb/1341848185.766700.png 1341848185.766730 depth/1341848185.766730.png
1341848185.802769 rgb/1341848185.802769.png 1341848185.802789 depth/1341848185.802789.png
1341848185.835178 rgb/1341848185.835178.png 1341848185.835190 depth/1341848185.835190.png
1341848185.867016 rgb/1341848185.867016.png 1341848185.867038 depth/1341848185.867038.png
1341848185.902852 rgb/1341848185.902852.png 1341848185.902864 depth/1341848185.902864.png
1341848185.934836 rgb/1341848185.934836.png 1341848185.934849 depth/1341848185.934849.png
1341848185.966743 rgb/1341848185.966743.png 1341848185.967338 depth/1341848185.967338.png
1341848186.002762 rgb/1341848186.002762.png 1341848186.002775 depth/1341848186.002775.png
1341848186.035920 rgb/1341848186.035920.png 1341848186.035991 depth/1341848186.035991.png
1341848186.070818 rgb/1341848186.070818.png 1341848186.070833 depth/1341848186.070833.png
1341848186.104189 rgb/1341848186.104189.png 1341848186.104201 depth/1341848186.104201.png
1341848186.134927 rgb/1341848186.134927.png 1341848186.134945 depth/1341848186.134945.png
1341848186.170915 rgb/1341848186.170915.png 1341848186.170933 depth/1341848186.170933.png
1341848186.202752 rgb/1341848186.202752.png 1341848186.202809 depth/1341848186.202809.png
1341848186.234733 rgb/1341848186.234733.png 1341848186.234750 depth/1341848186.234750.png
1341848186.270741 rgb/1341848186.270741.png 1341848186.270754 depth/1341848186.270754.png
1341848186.303057 rgb/1341848186.303057.png 1341848186.303113 depth/1341848186.303113.png
1341848186.338796 rgb/1341848186.338796.png 1341848186.338815 depth/1341848186.338815.png
1341848186.371367 rgb/1341848186.371367.png 1341848186.371378 depth/1341848186.371378.png
1341848186.403019 rgb/1341848186.403019.png 1341848186.403036 depth/1341848186.403036.png
1341848186.438815 rgb/1341848186.438815.png 1341848186.438862 depth/1341848186.438862.png
1341848186.470927 rgb/1341848186.470927.png 1341848186.471034 depth/1341848186.471034.png
1341848186.506851 rgb/1341848186.506851.png 1341848186.506863 depth/1341848186.506863.png
1341848186.538819 rgb/1341848186.538819.png 1341848186.538849 depth/1341848186.538849.png
1341848186.570755 rgb/1341848186.570755.png 1341848186.570773 depth/1341848186.570773.png
1341848186.606871 rgb/1341848186.606871.png 1341848186.606887 depth/1341848186.606887.png
1341848186.638840 rgb/1341848186.638840.png 1341848186.638868 depth/1341848186.638868.png
1341848186.670822 rgb/1341848186.670822.png 1341848186.670833 depth/1341848186.670833.png
1341848186.706944 rgb/1341848186.706944.png 1341848186.706972 depth/1341848186.706972.png
1341848186.738917 rgb/1341848186.738917.png 1341848186.739498 depth/1341848186.739498.png
1341848186.774956 rgb/1341848186.774956.png 1341848186.774979 depth/1341848186.774979.png
1341848186.806841 rgb/1341848186.806841.png 1341848186.806892 depth/1341848186.806892.png
1341848186.838838 rgb/1341848186.838838.png 1341848186.838869 depth/1341848186.838869.png
1341848186.874737 rgb/1341848186.874737.png 1341848186.874754 depth/1341848186.874754.png
1341848186.907104 rgb/1341848186.907104.png 1341848186.907119 depth/1341848186.907119.png
1341848186.939189 rgb/1341848186.939189.png 1341848186.939204 depth/1341848186.939204.png
1341848186.974895 rgb/1341848186.974895.png 1341848186.974909 depth/1341848186.974909.png
1341848187.007030 rgb/1341848187.007030.png 1341848187.007056 depth/1341848187.007056.png
1341848187.042759 rgb/1341848187.042759.png 1341848187.042819 depth/1341848187.042819.png
1341848187.074979 rgb/1341848187.074979.png 1341848187.075008 depth/1341848187.075008.png
1341848187.106865 rgb/1341848187.106865.png 1341848187.106892 depth/1341848187.106892.png
1341848187.142768 rgb/1341848187.142768.png 1341848187.142793 depth/1341848187.142793.png
1341848187.174798 rgb/1341848187.174798.png 1341848187.174827 depth/1341848187.174827.png
1341848187.206911 rgb/1341848187.206911.png 1341848187.206944 depth/1341848187.206944.png
1341848187.242938 rgb/1341848187.242938.png 1341848187.242944 depth/1341848187.242944.png
1341848187.274759 rgb/1341848187.274759.png 1341848187.274793 depth/1341848187.274793.png
1341848187.310802 rgb/1341848187.310802.png 1341848187.310853 depth/1341848187.310853.png
1341848187.343078 rgb/1341848187.343078.png 1341848187.343092 depth/1341848187.343092.png
1341848187.374872 rgb/1341848187.374872.png 1341848187.374884 depth/1341848187.374884.png
1341848187.410971 rgb/1341848187.410971.png 1341848187.411023 depth/1341848187.411023.png
1341848187.442872 rgb/1341848187.442872.png 1341848187.443310 depth/1341848187.443310.png
1341848187.474810 rgb/1341848187.474810.png 1341848187.474827 depth/1341848187.474827.png
1341848187.542858 rgb/1341848187.542858.png 1341848187.542870 depth/1341848187.542870.png
1341848187.578887 rgb/1341848187.578887.png 1341848187.578902 depth/1341848187.578902.png
1341848187.611097 rgb/1341848187.611097.png 1341848187.611220 depth/1341848187.611220.png
1341848187.642941 rgb/1341848187.642941.png 1341848187.642958 depth/1341848187.642958.png
1341848187.678820 rgb/1341848187.678820.png 1341848187.678834 depth/1341848187.678834.png
1341848187.710928 rgb/1341848187.710928.png 1341848187.710946 depth/1341848187.710946.png
1341848187.746857 rgb/1341848187.746857.png 1341848187.746895 depth/1341848187.746895.png
1341848187.778836 rgb/1341848187.778836.png 1341848187.778882 depth/1341848187.778882.png
1341848187.810862 rgb/1341848187.810862.png 1341848187.811327 depth/1341848187.811327.png
1341848187.846908 rgb/1341848187.846908.png 1341848187.846926 depth/1341848187.846926.png
1341848187.878820 rgb/1341848187.878820.png 1341848187.878850 depth/1341848187.878850.png
1341848187.910957 rgb/1341848187.910957.png 1341848187.911453 depth/1341848187.911453.png
1341848187.946783 rgb/1341848187.946783.png 1341848187.946799 depth/1341848187.946799.png
1341848187.979054 rgb/1341848187.979054.png 1341848187.979799 depth/1341848187.979799.png
1341848188.014878 rgb/1341848188.014878.png 1341848188.014896 depth/1341848188.014896.png
1341848188.078917 rgb/1341848188.078917.png 1341848188.079000 depth/1341848188.079000.png
1341848188.114776 rgb/1341848188.114776.png 1341848188.114814 depth/1341848188.114814.png
1341848188.146805 rgb/1341848188.146805.png 1341848188.146815 depth/1341848188.146815.png
1341848188.178816 rgb/1341848188.178816.png 1341848188.178832 depth/1341848188.178832.png
1341848188.214845 rgb/1341848188.214845.png 1341848188.214861 depth/1341848188.214861.png
1341848188.246728 rgb/1341848188.246728.png 1341848188.246765 depth/1341848188.246765.png
1341848188.282853 rgb/1341848188.282853.png 1341848188.282879 depth/1341848188.282879.png
1341848188.314763 rgb/1341848188.314763.png 1341848188.314778 depth/1341848188.314778.png
1341848188.346730 rgb/1341848188.346730.png 1341848188.346746 depth/1341848188.346746.png
1341848188.382923 rgb/1341848188.382923.png 1341848188.382961 depth/1341848188.382961.png
1341848188.414702 rgb/1341848188.414702.png 1341848188.414760 depth/1341848188.414760.png
1341848188.446758 rgb/1341848188.446758.png 1341848188.446790 depth/1341848188.446790.png
1341848188.482821 rgb/1341848188.482821.png 1341848188.482839 depth/1341848188.482839.png
1341848188.514758 rgb/1341848188.514758.png 1341848188.514783 depth/1341848188.514783.png
1341848188.550769 rgb/1341848188.550769.png 1341848188.550778 depth/1341848188.550778.png
1341848188.582859 rgb/1341848188.582859.png 1341848188.582924 depth/1341848188.582924.png
1341848188.614825 rgb/1341848188.614825.png 1341848188.614847 depth/1341848188.614847.png
1341848188.650735 rgb/1341848188.650735.png 1341848188.650747 depth/1341848188.650747.png
1341848188.682739 rgb/1341848188.682739.png 1341848188.682814 depth/1341848188.682814.png
1341848188.718925 rgb/1341848188.718925.png 1341848188.718956 depth/1341848188.718956.png
1341848188.750747 rgb/1341848188.750747.png 1341848188.750809 depth/1341848188.750809.png
1341848188.782762 rgb/1341848188.782762.png 1341848188.782822 depth/1341848188.782822.png
1341848188.818869 rgb/1341848188.818869.png 1341848188.818889 depth/1341848188.818889.png
1341848188.850792 rgb/1341848188.850792.png 1341848188.850814 depth/1341848188.850814.png
1341848188.882796 rgb/1341848188.882796.png 1341848188.882813 depth/1341848188.882813.png
1341848188.918907 rgb/1341848188.918907.png 1341848188.918938 depth/1341848188.918938.png
1341848188.950722 rgb/1341848188.950722.png 1341848188.950748 depth/1341848188.950748.png
1341848188.986792 rgb/1341848188.986792.png 1341848188.986827 depth/1341848188.986827.png
1341848189.018852 rgb/1341848189.018852.png 1341848189.018893 depth/1341848189.018893.png
1341848189.050770 rgb/1341848189.050770.png 1341848189.050844 depth/1341848189.050844.png
1341848189.086823 rgb/1341848189.086823.png 1341848189.086849 depth/1341848189.086849.png
1341848189.118952 rgb/1341848189.118952.png 1341848189.118978 depth/1341848189.118978.png
1341848189.151109 rgb/1341848189.151109.png 1341848189.151143 depth/1341848189.151143.png
1341848189.186736 rgb/1341848189.186736.png 1341848189.186797 depth/1341848189.186797.png
1341848189.218765 rgb/1341848189.218765.png 1341848189.218784 depth/1341848189.218784.png
1341848189.254854 rgb/1341848189.254854.png 1341848189.254872 depth/1341848189.254872.png
1341848189.286701 rgb/1341848189.286701.png 1341848189.286714 depth/1341848189.286714.png
1341848189.318786 rgb/1341848189.318786.png 1341848189.318803 depth/1341848189.318803.png
1341848189.354799 rgb/1341848189.354799.png 1341848189.354823 depth/1341848189.354823.png
1341848189.386799 rgb/1341848189.386799.png 1341848189.386814 depth/1341848189.386814.png
1341848189.418802 rgb/1341848189.418802.png 1341848189.418824 depth/1341848189.418824.png
1341848189.454737 rgb/1341848189.454737.png 1341848189.454751 depth/1341848189.454751.png
1341848189.486994 rgb/1341848189.486994.png 1341848189.487013 depth/1341848189.487013.png
1341848189.522909 rgb/1341848189.522909.png 1341848189.522927 depth/1341848189.522927.png
1341848189.554934 rgb/1341848189.554934.png 1341848189.554960 depth/1341848189.554960.png
1341848189.586795 rgb/1341848189.586795.png 1341848189.586815 depth/1341848189.586815.png
1341848189.622819 rgb/1341848189.622819.png 1341848189.622834 depth/1341848189.622834.png
1341848189.654834 rgb/1341848189.654834.png 1341848189.654847 depth/1341848189.654847.png
1341848189.686806 rgb/1341848189.686806.png 1341848189.686820 depth/1341848189.686820.png
1341848189.722778 rgb/1341848189.722778.png 1341848189.722796 depth/1341848189.722796.png
1341848189.754949 rgb/1341848189.754949.png 1341848189.754963 depth/1341848189.754963.png
1341848189.790766 rgb/1341848189.790766.png 1341848189.790778 depth/1341848189.790778.png
1341848189.822777 rgb/1341848189.822777.png 1341848189.822796 depth/1341848189.822796.png
1341848189.854983 rgb/1341848189.854983.png 1341848189.855043 depth/1341848189.855043.png
1341848189.890808 rgb/1341848189.890808.png 1341848189.890820 depth/1341848189.890820.png
1341848189.922740 rgb/1341848189.922740.png 1341848189.922760 depth/1341848189.922760.png
1341848189.958787 rgb/1341848189.958787.png 1341848189.958803 depth/1341848189.958803.png
1341848189.990836 rgb/1341848189.990836.png 1341848189.990855 depth/1341848189.990855.png
1341848190.022733 rgb/1341848190.022733.png 1341848190.022749 depth/1341848190.022749.png
1341848190.058877 rgb/1341848190.058877.png 1341848190.058890 depth/1341848190.058890.png
1341848190.090790 rgb/1341848190.090790.png 1341848190.090822 depth/1341848190.090822.png
1341848190.122792 rgb/1341848190.122792.png 1341848190.122807 depth/1341848190.122807.png
1341848190.158945 rgb/1341848190.158945.png 1341848190.159024 depth/1341848190.159024.png
1341848190.190775 rgb/1341848190.190775.png 1341848190.190798 depth/1341848190.190798.png
1341848190.226741 rgb/1341848190.226741.png 1341848190.226768 depth/1341848190.226768.png
1341848190.258940 rgb/1341848190.258940.png 1341848190.258963 depth/1341848190.258963.png
1341848190.290895 rgb/1341848190.290895.png 1341848190.290916 depth/1341848190.290916.png
1341848190.326837 rgb/1341848190.326837.png 1341848190.326845 depth/1341848190.326845.png
1341848190.358768 rgb/1341848190.358768.png 1341848190.358798 depth/1341848190.358798.png
1341848190.390849 rgb/1341848190.390849.png 1341848190.390883 depth/1341848190.390883.png
1341848190.426804 rgb/1341848190.426804.png 1341848190.426813 depth/1341848190.426813.png
1341848190.458850 rgb/1341848190.458850.png 1341848190.458860 depth/1341848190.458860.png
1341848190.494754 rgb/1341848190.494754.png 1341848190.495376 depth/1341848190.495376.png
1341848190.526846 rgb/1341848190.526846.png 1341848190.526880 depth/1341848190.526880.png
1341848190.558835 rgb/1341848190.558835.png 1341848190.558903 depth/1341848190.558903.png
1341848190.594853 rgb/1341848190.594853.png 1341848190.594881 depth/1341848190.594881.png
1341848190.626791 rgb/1341848190.626791.png 1341848190.626812 depth/1341848190.626812.png
1341848190.658825 rgb/1341848190.658825.png 1341848190.659389 depth/1341848190.659389.png
1341848190.694907 rgb/1341848190.694907.png 1341848190.694929 depth/1341848190.694929.png
1341848190.726928 rgb/1341848190.726928.png 1341848190.726957 depth/1341848190.726957.png
1341848190.762690 rgb/1341848190.762690.png 1341848190.762798 depth/1341848190.762798.png
1341848190.795329 rgb/1341848190.795329.png 1341848190.796398 depth/1341848190.796398.png
1341848190.830460 rgb/1341848190.830460.png 1341848190.831560 depth/1341848190.831560.png
1341848190.862959 rgb/1341848190.862959.png 1341848190.864285 depth/1341848190.864285.png
1341848190.895655 rgb/1341848190.895655.png 1341848190.895788 depth/1341848190.895788.png
1341848190.934402 rgb/1341848190.934402.png 1341848190.934549 depth/1341848190.934549.png
1341848190.995265 rgb/1341848190.995265.png 1341848190.996289 depth/1341848190.996289.png
1341848191.031588 rgb/1341848191.031588.png 1341848191.032619 depth/1341848191.032619.png
1341848191.063534 rgb/1341848191.063534.png 1341848191.064315 depth/1341848191.064315.png
1341848191.097226 rgb/1341848191.097226.png 1341848191.098545 depth/1341848191.098545.png
1341848191.131193 rgb/1341848191.131193.png 1341848191.132055 depth/1341848191.132055.png
1341848191.164701 rgb/1341848191.164701.png 1341848191.165452 depth/1341848191.165452.png
1341848191.199172 rgb/1341848191.199172.png 1341848191.199448 depth/1341848191.199448.png
1341848191.233289 rgb/1341848191.233289.png 1341848191.234296 depth/1341848191.234296.png
1341848191.263719 rgb/1341848191.263719.png 1341848191.265304 depth/1341848191.265304.png
1341848191.300981 rgb/1341848191.300981.png 1341848191.301008 depth/1341848191.301008.png
1341848191.333151 rgb/1341848191.333151.png 1341848191.339200 depth/1341848191.339200.png
1341848191.370918 rgb/1341848191.370918.png 1341848191.371605 depth/1341848191.371605.png
1341848191.430736 rgb/1341848191.430736.png 1341848191.430761 depth/1341848191.430761.png
1341848191.466799 rgb/1341848191.466799.png 1341848191.466812 depth/1341848191.466812.png
1341848191.498796 rgb/1341848191.498796.png 1341848191.499405 depth/1341848191.499405.png
1341848191.531077 rgb/1341848191.531077.png 1341848191.531102 depth/1341848191.531102.png
1341848191.566739 rgb/1341848191.566739.png 1341848191.566748 depth/1341848191.566748.png
1341848191.598772 rgb/1341848191.598772.png 1341848191.598830 depth/1341848191.598830.png
1341848191.630977 rgb/1341848191.630977.png 1341848191.631023 depth/1341848191.631023.png
1341848191.666746 rgb/1341848191.666746.png 1341848191.666800 depth/1341848191.666800.png
1341848191.698747 rgb/1341848191.698747.png 1341848191.698756 depth/1341848191.698756.png
1341848191.734825 rgb/1341848191.734825.png 1341848191.734837 depth/1341848191.734837.png
1341848191.767006 rgb/1341848191.767006.png 1341848191.767029 depth/1341848191.767029.png
1341848191.798875 rgb/1341848191.798875.png 1341848191.798894 depth/1341848191.798894.png
1341848191.834902 rgb/1341848191.834902.png 1341848191.834921 depth/1341848191.834921.png
1341848191.866803 rgb/1341848191.866803.png 1341848191.867085 depth/1341848191.867085.png
1341848191.902776 rgb/1341848191.902776.png 1341848191.902846 depth/1341848191.902846.png
1341848191.935119 rgb/1341848191.935119.png 1341848191.935135 depth/1341848191.935135.png
1341848191.967132 rgb/1341848191.967132.png 1341848191.967158 depth/1341848191.967158.png
1341848192.002746 rgb/1341848192.002746.png 1341848192.002932 depth/1341848192.002932.png
1341848192.034845 rgb/1341848192.034845.png 1341848192.034861 depth/1341848192.034861.png
1341848192.066940 rgb/1341848192.066940.png 1341848192.066959 depth/1341848192.066959.png
1341848192.102735 rgb/1341848192.102735.png 1341848192.102764 depth/1341848192.102764.png
1341848192.134732 rgb/1341848192.134732.png 1341848192.134739 depth/1341848192.134739.png
1341848192.170709 rgb/1341848192.170709.png 1341848192.170722 depth/1341848192.170722.png
1341848192.202746 rgb/1341848192.202746.png 1341848192.203061 depth/1341848192.203061.png
1341848192.234742 rgb/1341848192.234742.png 1341848192.234756 depth/1341848192.234756.png
1341848192.270771 rgb/1341848192.270771.png 1341848192.270783 depth/1341848192.270783.png
1341848192.302839 rgb/1341848192.302839.png 1341848192.302858 depth/1341848192.302858.png
1341848192.334855 rgb/1341848192.334855.png 1341848192.334906 depth/1341848192.334906.png
1341848192.370935 rgb/1341848192.370935.png 1341848192.370972 depth/1341848192.370972.png
1341848192.403681 rgb/1341848192.403681.png 1341848192.403733 depth/1341848192.403733.png
1341848192.438774 rgb/1341848192.438774.png 1341848192.438839 depth/1341848192.438839.png
1341848192.470963 rgb/1341848192.470963.png 1341848192.471392 depth/1341848192.471392.png
1341848192.502796 rgb/1341848192.502796.png 1341848192.502820 depth/1341848192.502820.png
1341848192.538767 rgb/1341848192.538767.png 1341848192.538806 depth/1341848192.538806.png
1341848192.570809 rgb/1341848192.570809.png 1341848192.570865 depth/1341848192.570865.png
1341848192.603078 rgb/1341848192.603078.png 1341848192.603091 depth/1341848192.603091.png
1341848192.638754 rgb/1341848192.638754.png 1341848192.638776 depth/1341848192.638776.png
1341848192.670852 rgb/1341848192.670852.png 1341848192.670879 depth/1341848192.670879.png
1341848192.706841 rgb/1341848192.706841.png 1341848192.706856 depth/1341848192.706856.png
1341848192.738829 rgb/1341848192.738829.png 1341848192.738842 depth/1341848192.738842.png
1341848192.806837 rgb/1341848192.806837.png 1341848192.806927 depth/1341848192.806927.png
1341848192.838968 rgb/1341848192.838968.png 1341848192.839206 depth/1341848192.839206.png
1341848192.870780 rgb/1341848192.870780.png 1341848192.870810 depth/1341848192.870810.png
1341848192.906762 rgb/1341848192.906762.png 1341848192.906773 depth/1341848192.906773.png
1341848192.938822 rgb/1341848192.938822.png 1341848192.939405 depth/1341848192.939405.png
1341848192.974836 rgb/1341848192.974836.png 1341848192.974854 depth/1341848192.974854.png
1341848193.006742 rgb/1341848193.006742.png 1341848193.006754 depth/1341848193.006754.png
1341848193.038794 rgb/1341848193.038794.png 1341848193.038906 depth/1341848193.038906.png
1341848193.074712 rgb/1341848193.074712.png 1341848193.074827 depth/1341848193.074827.png
1341848193.106799 rgb/1341848193.106799.png 1341848193.106833 depth/1341848193.106833.png
1341848193.143055 rgb/1341848193.143055.png 1341848193.143097 depth/1341848193.143097.png
1341848193.174711 rgb/1341848193.174711.png 1341848193.174723 depth/1341848193.174723.png
1341848193.206858 rgb/1341848193.206858.png 1341848193.206879 depth/1341848193.206879.png
1341848193.243077 rgb/1341848193.243077.png 1341848193.243089 depth/1341848193.243089.png
1341848193.274812 rgb/1341848193.274812.png 1341848193.274832 depth/1341848193.274832.png
1341848193.306867 rgb/1341848193.306867.png 1341848193.306910 depth/1341848193.306910.png
1341848193.342800 rgb/1341848193.342800.png 1341848193.342814 depth/1341848193.342814.png
1341848193.374866 rgb/1341848193.374866.png 1341848193.374898 depth/1341848193.374898.png
1341848193.411036 rgb/1341848193.411036.png 1341848193.411075 depth/1341848193.411075.png
1341848193.442761 rgb/1341848193.442761.png 1341848193.442804 depth/1341848193.442804.png
1341848193.475010 rgb/1341848193.475010.png 1341848193.475024 depth/1341848193.475024.png
1341848193.510846 rgb/1341848193.510846.png 1341848193.510864 depth/1341848193.510864.png
1341848193.542938 rgb/1341848193.542938.png 1341848193.542956 depth/1341848193.542956.png
1341848193.574998 rgb/1341848193.574998.png 1341848193.575058 depth/1341848193.575058.png
1341848193.610916 rgb/1341848193.610916.png 1341848193.610933 depth/1341848193.610933.png
1341848193.642828 rgb/1341848193.642828.png 1341848193.642850 depth/1341848193.642850.png
1341848193.678889 rgb/1341848193.678889.png 1341848193.678905 depth/1341848193.678905.png
1341848193.710859 rgb/1341848193.710859.png 1341848193.710872 depth/1341848193.710872.png
1341848193.742793 rgb/1341848193.742793.png 1341848193.742810 depth/1341848193.742810.png
1341848193.778731 rgb/1341848193.778731.png 1341848193.778786 depth/1341848193.778786.png
1341848193.810840 rgb/1341848193.810840.png 1341848193.810861 depth/1341848193.810861.png
1341848193.842730 rgb/1341848193.842730.png 1341848193.842748 depth/1341848193.842748.png
1341848193.878943 rgb/1341848193.878943.png 1341848193.878976 depth/1341848193.878976.png
1341848193.910802 rgb/1341848193.910802.png 1341848193.910829 depth/1341848193.910829.png
1341848193.946793 rgb/1341848193.946793.png 1341848193.946814 depth/1341848193.946814.png
1341848193.979155 rgb/1341848193.979155.png 1341848193.979184 depth/1341848193.979184.png
1341848194.010983 rgb/1341848194.010983.png 1341848194.011120 depth/1341848194.011120.png
1341848194.046907 rgb/1341848194.046907.png 1341848194.046929 depth/1341848194.046929.png
1341848194.079166 rgb/1341848194.079166.png 1341848194.079185 depth/1341848194.079185.png
1341848194.114789 rgb/1341848194.114789.png 1341848194.114859 depth/1341848194.114859.png
1341848194.146801 rgb/1341848194.146801.png 1341848194.146818 depth/1341848194.146818.png
1341848194.178845 rgb/1341848194.178845.png 1341848194.179487 depth/1341848194.179487.png
1341848194.214831 rgb/1341848194.214831.png 1341848194.214868 depth/1341848194.214868.png
1341848194.246769 rgb/1341848194.246769.png 1341848194.246825 depth/1341848194.246825.png
1341848194.278847 rgb/1341848194.278847.png 1341848194.278866 depth/1341848194.278866.png
1341848194.314986 rgb/1341848194.314986.png 1341848194.315001 depth/1341848194.315001.png
1341848194.346744 rgb/1341848194.346744.png 1341848194.346772 depth/1341848194.346772.png
1341848194.382869 rgb/1341848194.382869.png 1341848194.383550 depth/1341848194.383550.png
1341848194.414913 rgb/1341848194.414913.png 1341848194.415539 depth/1341848194.415539.png
1341848194.446890 rgb/1341848194.446890.png 1341848194.447617 depth/1341848194.447617.png
1341848194.482836 rgb/1341848194.482836.png 1341848194.482848 depth/1341848194.482848.png
1341848194.514853 rgb/1341848194.514853.png 1341848194.514878 depth/1341848194.514878.png
1341848194.546817 rgb/1341848194.546817.png 1341848194.547527 depth/1341848194.547527.png
1341848194.582746 rgb/1341848194.582746.png 1341848194.582798 depth/1341848194.582798.png
1341848194.614770 rgb/1341848194.614770.png 1341848194.614789 depth/1341848194.614789.png
1341848194.650770 rgb/1341848194.650770.png 1341848194.651512 depth/1341848194.651512.png
1341848194.682992 rgb/1341848194.682992.png 1341848194.683577 depth/1341848194.683577.png
1341848194.714785 rgb/1341848194.714785.png 1341848194.714797 depth/1341848194.714797.png
1341848194.750817 rgb/1341848194.750817.png 1341848194.750833 depth/1341848194.750833.png
1341848194.782900 rgb/1341848194.782900.png 1341848194.782917 depth/1341848194.782917.png
1341848194.814840 rgb/1341848194.814840.png 1341848194.814856 depth/1341848194.814856.png
1341848194.850846 rgb/1341848194.850846.png 1341848194.850892 depth/1341848194.850892.png
1341848194.882844 rgb/1341848194.882844.png 1341848194.883389 depth/1341848194.883389.png
1341848194.926022 rgb/1341848194.926022.png 1341848194.926062 depth/1341848194.926062.png
1341848194.982933 rgb/1341848194.982933.png 1341848194.982946 depth/1341848194.982946.png
1341848195.018896 rgb/1341848195.018896.png 1341848195.018930 depth/1341848195.018930.png
1341848195.050981 rgb/1341848195.050981.png 1341848195.051000 depth/1341848195.051000.png
1341848195.082839 rgb/1341848195.082839.png 1341848195.082857 depth/1341848195.082857.png
1341848195.118823 rgb/1341848195.118823.png 1341848195.118838 depth/1341848195.118838.png
1341848195.150804 rgb/1341848195.150804.png 1341848195.150822 depth/1341848195.150822.png
1341848195.186782 rgb/1341848195.186782.png 1341848195.186820 depth/1341848195.186820.png
1341848195.218821 rgb/1341848195.218821.png 1341848195.218832 depth/1341848195.218832.png
1341848195.250899 rgb/1341848195.250899.png 1341848195.250921 depth/1341848195.250921.png
1341848195.286795 rgb/1341848195.286795.png 1341848195.286842 depth/1341848195.286842.png
1341848195.318715 rgb/1341848195.318715.png 1341848195.318750 depth/1341848195.318750.png
1341848195.354786 rgb/1341848195.354786.png 1341848195.354831 depth/1341848195.354831.png
1341848195.387291 rgb/1341848195.387291.png 1341848195.387337 depth/1341848195.387337.png
1341848195.418986 rgb/1341848195.418986.png 1341848195.419025 depth/1341848195.419025.png
1341848195.454859 rgb/1341848195.454859.png 1341848195.454879 depth/1341848195.454879.png
1341848195.486776 rgb/1341848195.486776.png 1341848195.487351 depth/1341848195.487351.png
1341848195.554952 rgb/1341848195.554952.png 1341848195.554992 depth/1341848195.554992.png
1341848195.586849 rgb/1341848195.586849.png 1341848195.586863 depth/1341848195.586863.png
1341848195.622889 rgb/1341848195.622889.png 1341848195.622900 depth/1341848195.622900.png
1341848195.686873 rgb/1341848195.686873.png 1341848195.686902 depth/1341848195.686902.png
1341848195.725831 rgb/1341848195.725831.png 1341848195.725880 depth/1341848195.725880.png
1341848195.762032 rgb/1341848195.762032.png 1341848195.762834 depth/1341848195.762834.png
1341848195.794177 rgb/1341848195.794177.png 1341848195.794930 depth/1341848195.794930.png
1341848195.825652 rgb/1341848195.825652.png 1341848195.826094 depth/1341848195.826094.png
1341848195.861783 rgb/1341848195.861783.png 1341848195.861817 depth/1341848195.861817.png
1341848195.893744 rgb/1341848195.893744.png 1341848195.893790 depth/1341848195.893790.png
1341848195.925713 rgb/1341848195.925713.png 1341848195.925725 depth/1341848195.925725.png
1341848195.961824 rgb/1341848195.961824.png 1341848195.961835 depth/1341848195.961835.png
1341848195.993912 rgb/1341848195.993912.png 1341848195.993945 depth/1341848195.993945.png
1341848196.026024 rgb/1341848196.026024.png 1341848196.026076 depth/1341848196.026076.png
1341848196.061848 rgb/1341848196.061848.png 1341848196.061861 depth/1341848196.061861.png
1341848196.094141 rgb/1341848196.094141.png 1341848196.095188 depth/1341848196.095188.png
1341848196.130674 rgb/1341848196.130674.png 1341848196.131229 depth/1341848196.131229.png
1341848196.162338 rgb/1341848196.162338.png 1341848196.163087 depth/1341848196.163087.png
1341848196.193818 rgb/1341848196.193818.png 1341848196.193838 depth/1341848196.193838.png
1341848196.229907 rgb/1341848196.229907.png 1341848196.229930 depth/1341848196.229930.png
1341848196.261955 rgb/1341848196.261955.png 1341848196.261976 depth/1341848196.261976.png
1341848196.297852 rgb/1341848196.297852.png 1341848196.297869 depth/1341848196.297869.png
1341848196.329896 rgb/1341848196.329896.png 1341848196.329951 depth/1341848196.329951.png
1341848196.361859 rgb/1341848196.361859.png 1341848196.361884 depth/1341848196.361884.png
1341848196.397904 rgb/1341848196.397904.png 1341848196.397928 depth/1341848196.397928.png
1341848196.429770 rgb/1341848196.429770.png 1341848196.429781 depth/1341848196.429781.png
1341848196.465837 rgb/1341848196.465837.png 1341848196.465853 depth/1341848196.465853.png
1341848196.497816 rgb/1341848196.497816.png 1341848196.497860 depth/1341848196.497860.png
1341848196.529784 rgb/1341848196.529784.png 1341848196.530168 depth/1341848196.530168.png
1341848196.565825 rgb/1341848196.565825.png 1341848196.565847 depth/1341848196.565847.png
1341848196.597724 rgb/1341848196.597724.png 1341848196.597735 depth/1341848196.597735.png
1341848196.633826 rgb/1341848196.633826.png 1341848196.633847 depth/1341848196.633847.png
1341848196.665890 rgb/1341848196.665890.png 1341848196.665900 depth/1341848196.665900.png
1341848196.697801 rgb/1341848196.697801.png 1341848196.697815 depth/1341848196.697815.png
1341848196.733819 rgb/1341848196.733819.png 1341848196.733834 depth/1341848196.733834.png
1341848196.765769 rgb/1341848196.765769.png 1341848196.766295 depth/1341848196.766295.png
1341848196.801859 rgb/1341848196.801859.png 1341848196.801884 depth/1341848196.801884.png
1341848196.833829 rgb/1341848196.833829.png 1341848196.833842 depth/1341848196.833842.png
1341848196.865816 rgb/1341848196.865816.png 1341848196.865844 depth/1341848196.865844.png
1341848196.901907 rgb/1341848196.901907.png 1341848196.901936 depth/1341848196.901936.png
1341848196.933819 rgb/1341848196.933819.png 1341848196.933829 depth/1341848196.933829.png
1341848196.969765 rgb/1341848196.969765.png 1341848196.969878 depth/1341848196.969878.png
1341848197.002186 rgb/1341848197.002186.png 1341848197.002523 depth/1341848197.002523.png
1341848197.033823 rgb/1341848197.033823.png 1341848197.033839 depth/1341848197.033839.png
1341848197.069833 rgb/1341848197.069833.png 1341848197.069845 depth/1341848197.069845.png
1341848197.101755 rgb/1341848197.101755.png 1341848197.101767 depth/1341848197.101767.png
1341848197.137743 rgb/1341848197.137743.png 1341848197.137756 depth/1341848197.137756.png
1341848197.169776 rgb/1341848197.169776.png 1341848197.169791 depth/1341848197.169791.png
1341848197.201768 rgb/1341848197.201768.png 1341848197.201782 depth/1341848197.201782.png
1341848197.237725 rgb/1341848197.237725.png 1341848197.237740 depth/1341848197.237740.png
1341848197.269696 rgb/1341848197.269696.png 1341848197.269718 depth/1341848197.269718.png
1341848197.305821 rgb/1341848197.305821.png 1341848197.305838 depth/1341848197.305838.png
1341848197.337836 rgb/1341848197.337836.png 1341848197.337847 depth/1341848197.337847.png
1341848197.369834 rgb/1341848197.369834.png 1341848197.369848 depth/1341848197.369848.png
1341848197.405781 rgb/1341848197.405781.png 1341848197.405964 depth/1341848197.405964.png
1341848197.438318 rgb/1341848197.438318.png 1341848197.439689 depth/1341848197.439689.png
1341848197.470331 rgb/1341848197.470331.png 1341848197.471280 depth/1341848197.471280.png
1341848197.506039 rgb/1341848197.506039.png 1341848197.506686 depth/1341848197.506686.png
1341848197.538237 rgb/1341848197.538237.png 1341848197.539353 depth/1341848197.539353.png
1341848197.570404 rgb/1341848197.570404.png 1341848197.570772 depth/1341848197.570772.png
1341848197.605996 rgb/1341848197.605996.png 1341848197.606026 depth/1341848197.606026.png
1341848197.673877 rgb/1341848197.673877.png 1341848197.674558 depth/1341848197.674558.png
1341848197.730726 rgb/1341848197.730726.png 1341848197.730737 depth/1341848197.730737.png
1341848197.766773 rgb/1341848197.766773.png 1341848197.766828 depth/1341848197.766828.png
1341848197.798803 rgb/1341848197.798803.png 1341848197.798910 depth/1341848197.798910.png
1341848197.834766 rgb/1341848197.834766.png 1341848197.835104 depth/1341848197.835104.png
1341848197.866760 rgb/1341848197.866760.png 1341848197.866779 depth/1341848197.866779.png
1341848197.898890 rgb/1341848197.898890.png 1341848197.898977 depth/1341848197.898977.png
1341848197.934813 rgb/1341848197.934813.png 1341848197.934847 depth/1341848197.934847.png
1341848197.966863 rgb/1341848197.966863.png 1341848197.966903 depth/1341848197.966903.png
1341848197.998770 rgb/1341848197.998770.png 1341848197.998785 depth/1341848197.998785.png
1341848198.034701 rgb/1341848198.034701.png 1341848198.034721 depth/1341848198.034721.png
1341848198.066721 rgb/1341848198.066721.png 1341848198.066734 depth/1341848198.066734.png
1341848198.102720 rgb/1341848198.102720.png 1341848198.102746 depth/1341848198.102746.png
1341848198.134867 rgb/1341848198.134867.png 1341848198.134882 depth/1341848198.134882.png
1341848198.166841 rgb/1341848198.166841.png 1341848198.166853 depth/1341848198.166853.png
1341848198.202735 rgb/1341848198.202735.png 1341848198.202750 depth/1341848198.202750.png
1341848198.234818 rgb/1341848198.234818.png 1341848198.234835 depth/1341848198.234835.png
1341848198.266823 rgb/1341848198.266823.png 1341848198.266901 depth/1341848198.266901.png
1341848198.302707 rgb/1341848198.302707.png 1341848198.302724 depth/1341848198.302724.png
1341848198.334907 rgb/1341848198.334907.png 1341848198.334919 depth/1341848198.334919.png
1341848198.370753 rgb/1341848198.370753.png 1341848198.370836 depth/1341848198.370836.png
1341848198.402766 rgb/1341848198.402766.png 1341848198.402778 depth/1341848198.402778.png
1341848198.434945 rgb/1341848198.434945.png 1341848198.434963 depth/1341848198.434963.png
1341848198.470794 rgb/1341848198.470794.png 1341848198.470819 depth/1341848198.470819.png
1341848198.503078 rgb/1341848198.503078.png 1341848198.503090 depth/1341848198.503090.png
1341848198.538846 rgb/1341848198.538846.png 1341848198.538864 depth/1341848198.538864.png
1341848198.570792 rgb/1341848198.570792.png 1341848198.570819 depth/1341848198.570819.png
1341848198.602794 rgb/1341848198.602794.png 1341848198.603133 depth/1341848198.603133.png
1341848198.638784 rgb/1341848198.638784.png 1341848198.638808 depth/1341848198.638808.png
1341848198.702910 rgb/1341848198.702910.png 1341848198.702925 depth/1341848198.702925.png
1341848198.738809 rgb/1341848198.738809.png 1341848198.739381 depth/1341848198.739381.png
1341848198.770831 rgb/1341848198.770831.png 1341848198.771382 depth/1341848198.771382.png
1341848198.806885 rgb/1341848198.806885.png 1341848198.806910 depth/1341848198.806910.png
1341848198.838811 rgb/1341848198.838811.png 1341848198.838846 depth/1341848198.838846.png
1341848198.870802 rgb/1341848198.870802.png 1341848198.870814 depth/1341848198.870814.png
1341848198.906904 rgb/1341848198.906904.png 1341848198.906918 depth/1341848198.906918.png
1341848198.939336 rgb/1341848198.939336.png 1341848198.939375 depth/1341848198.939375.png
1341848198.970809 rgb/1341848198.970809.png 1341848198.970818 depth/1341848198.970818.png
1341848199.006748 rgb/1341848199.006748.png 1341848199.006761 depth/1341848199.006761.png
1341848199.038736 rgb/1341848199.038736.png 1341848199.038754 depth/1341848199.038754.png
1341848199.074703 rgb/1341848199.074703.png 1341848199.074717 depth/1341848199.074717.png
1341848199.106951 rgb/1341848199.106951.png 1341848199.107013 depth/1341848199.107013.png
1341848199.139453 rgb/1341848199.139453.png 1341848199.139496 depth/1341848199.139496.png
1341848199.174845 rgb/1341848199.174845.png 1341848199.174865 depth/1341848199.174865.png
1341848199.206807 rgb/1341848199.206807.png 1341848199.206823 depth/1341848199.206823.png
1341848199.239202 rgb/1341848199.239202.png 1341848199.239894 depth/1341848199.239894.png
1341848199.274874 rgb/1341848199.274874.png 1341848199.274916 depth/1341848199.274916.png
1341848199.306884 rgb/1341848199.306884.png 1341848199.306911 depth/1341848199.306911.png
1341848199.342847 rgb/1341848199.342847.png 1341848199.342860 depth/1341848199.342860.png
1341848199.374778 rgb/1341848199.374778.png 1341848199.374801 depth/1341848199.374801.png
1341848199.406857 rgb/1341848199.406857.png 1341848199.406871 depth/1341848199.406871.png
1341848199.442805 rgb/1341848199.442805.png 1341848199.442829 depth/1341848199.442829.png
1341848199.474838 rgb/1341848199.474838.png 1341848199.474851 depth/1341848199.474851.png
1341848199.506816 rgb/1341848199.506816.png 1341848199.506828 depth/1341848199.506828.png
1341848199.542775 rgb/1341848199.542775.png 1341848199.542786 depth/1341848199.542786.png
1341848199.574762 rgb/1341848199.574762.png 1341848199.574910 depth/1341848199.574910.png
1341848199.610813 rgb/1341848199.610813.png 1341848199.610851 depth/1341848199.610851.png
1341848199.642767 rgb/1341848199.642767.png 1341848199.643520 depth/1341848199.643520.png
1341848199.674895 rgb/1341848199.674895.png 1341848199.674909 depth/1341848199.674909.png
1341848199.711005 rgb/1341848199.711005.png 1341848199.711038 depth/1341848199.711038.png
1341848199.742803 rgb/1341848199.742803.png 1341848199.742854 depth/1341848199.742854.png
1341848199.778818 rgb/1341848199.778818.png 1341848199.778833 depth/1341848199.778833.png
1341848199.810902 rgb/1341848199.810902.png 1341848199.810928 depth/1341848199.810928.png
1341848199.842807 rgb/1341848199.842807.png 1341848199.842855 depth/1341848199.842855.png
1341848199.878917 rgb/1341848199.878917.png 1341848199.878937 depth/1341848199.878937.png
1341848199.910786 rgb/1341848199.910786.png 1341848199.910805 depth/1341848199.910805.png
1341848199.942791 rgb/1341848199.942791.png 1341848199.942807 depth/1341848199.942807.png
1341848199.978875 rgb/1341848199.978875.png 1341848199.978884 depth/1341848199.978884.png
1341848200.011490 rgb/1341848200.011490.png 1341848200.011625 depth/1341848200.011625.png
1341848200.046911 rgb/1341848200.046911.png 1341848200.046921 depth/1341848200.046921.png
1341848200.078729 rgb/1341848200.078729.png 1341848200.078745 depth/1341848200.078745.png
1341848200.110758 rgb/1341848200.110758.png 1341848200.110784 depth/1341848200.110784.png
1341848200.146848 rgb/1341848200.146848.png 1341848200.146908 depth/1341848200.146908.png
1341848200.178939 rgb/1341848200.178939.png 1341848200.178975 depth/1341848200.178975.png
1341848200.210812 rgb/1341848200.210812.png 1341848200.210843 depth/1341848200.210843.png
1341848200.246881 rgb/1341848200.246881.png 1341848200.246934 depth/1341848200.246934.png
1341848200.314856 rgb/1341848200.314856.png 1341848200.314894 depth/1341848200.314894.png
1341848200.347670 rgb/1341848200.347670.png 1341848200.348040 depth/1341848200.348040.png
1341848200.380010 rgb/1341848200.380010.png 1341848200.380545 depth/1341848200.380545.png
1341848200.414932 rgb/1341848200.414932.png 1341848200.414956 depth/1341848200.414956.png
1341848200.446767 rgb/1341848200.446767.png 1341848200.446788 depth/1341848200.446788.png
1341848200.478797 rgb/1341848200.478797.png 1341848200.478825 depth/1341848200.478825.png
1341848200.514818 rgb/1341848200.514818.png 1341848200.514829 depth/1341848200.514829.png
1341848200.546874 rgb/1341848200.546874.png 1341848200.546910 depth/1341848200.546910.png
1341848200.582800 rgb/1341848200.582800.png 1341848200.582833 depth/1341848200.582833.png
1341848200.614903 rgb/1341848200.614903.png 1341848200.614923 depth/1341848200.614923.png
1341848200.647716 rgb/1341848200.647716.png 1341848200.647741 depth/1341848200.647741.png
1341848200.682823 rgb/1341848200.682823.png 1341848200.682832 depth/1341848200.682832.png
1341848200.714755 rgb/1341848200.714755.png 1341848200.714825 depth/1341848200.714825.png
1341848200.750866 rgb/1341848200.750866.png 1341848200.750888 depth/1341848200.750888.png
1341848200.782776 rgb/1341848200.782776.png 1341848200.782809 depth/1341848200.782809.png
1341848200.814970 rgb/1341848200.814970.png 1341848200.815000 depth/1341848200.815000.png
1341848200.851857 rgb/1341848200.851857.png 1341848200.851908 depth/1341848200.851908.png
1341848200.882746 rgb/1341848200.882746.png 1341848200.884262 depth/1341848200.884262.png
1341848200.914831 rgb/1341848200.914831.png 1341848200.914846 depth/1341848200.914846.png
1341848200.950898 rgb/1341848200.950898.png 1341848200.951501 depth/1341848200.951501.png
1341848200.982959 rgb/1341848200.982959.png 1341848200.983489 depth/1341848200.983489.png
1341848201.018858 rgb/1341848201.018858.png 1341848201.018888 depth/1341848201.018888.png
1341848201.082903 rgb/1341848201.082903.png 1341848201.082925 depth/1341848201.082925.png
1341848201.118825 rgb/1341848201.118825.png 1341848201.118892 depth/1341848201.118892.png
1341848201.150778 rgb/1341848201.150778.png 1341848201.150797 depth/1341848201.150797.png
1341848201.182792 rgb/1341848201.182792.png 1341848201.182806 depth/1341848201.182806.png
1341848201.218704 rgb/1341848201.218704.png 1341848201.218729 depth/1341848201.218729.png
1341848201.250866 rgb/1341848201.250866.png 1341848201.250896 depth/1341848201.250896.png
1341848201.286761 rgb/1341848201.286761.png 1341848201.287237 depth/1341848201.287237.png
1341848201.318840 rgb/1341848201.318840.png 1341848201.318863 depth/1341848201.318863.png
1341848201.350770 rgb/1341848201.350770.png 1341848201.350798 depth/1341848201.350798.png
1341848201.386844 rgb/1341848201.386844.png 1341848201.386867 depth/1341848201.386867.png
1341848201.418704 rgb/1341848201.418704.png 1341848201.418721 depth/1341848201.418721.png
1341848201.450753 rgb/1341848201.450753.png 1341848201.450769 depth/1341848201.450769.png
1341848201.486867 rgb/1341848201.486867.png 1341848201.486884 depth/1341848201.486884.png
1341848201.518787 rgb/1341848201.518787.png 1341848201.518823 depth/1341848201.518823.png
1341848201.554850 rgb/1341848201.554850.png 1341848201.554880 depth/1341848201.554880.png
1341848201.586810 rgb/1341848201.586810.png 1341848201.586829 depth/1341848201.586829.png
1341848201.619029 rgb/1341848201.619029.png 1341848201.619048 depth/1341848201.619048.png
1341848201.654905 rgb/1341848201.654905.png 1341848201.654966 depth/1341848201.654966.png
1341848201.686809 rgb/1341848201.686809.png 1341848201.686870 depth/1341848201.686870.png
1341848201.718889 rgb/1341848201.718889.png 1341848201.718959 depth/1341848201.718959.png
1341848201.754827 rgb/1341848201.754827.png 1341848201.754846 depth/1341848201.754846.png
1341848201.787472 rgb/1341848201.787472.png 1341848201.788288 depth/1341848201.788288.png
1341848201.822831 rgb/1341848201.822831.png 1341848201.822854 depth/1341848201.822854.png
1341848201.854857 rgb/1341848201.854857.png 1341848201.854877 depth/1341848201.854877.png
1341848201.886841 rgb/1341848201.886841.png 1341848201.886885 depth/1341848201.886885.png
1341848201.922874 rgb/1341848201.922874.png 1341848201.922885 depth/1341848201.922885.png
1341848201.954804 rgb/1341848201.954804.png 1341848201.954842 depth/1341848201.954842.png
1341848201.990851 rgb/1341848201.990851.png 1341848201.990862 depth/1341848201.990862.png
1341848202.022777 rgb/1341848202.022777.png 1341848202.022791 depth/1341848202.022791.png
1341848202.054887 rgb/1341848202.054887.png 1341848202.054898 depth/1341848202.054898.png
1341848202.090885 rgb/1341848202.090885.png 1341848202.090901 depth/1341848202.090901.png
1341848202.122835 rgb/1341848202.122835.png 1341848202.122856 depth/1341848202.122856.png
1341848202.154813 rgb/1341848202.154813.png 1341848202.154887 depth/1341848202.154887.png
1341848202.190789 rgb/1341848202.190789.png 1341848202.190821 depth/1341848202.190821.png
1341848202.222712 rgb/1341848202.222712.png 1341848202.222724 depth/1341848202.222724.png
1341848202.258821 rgb/1341848202.258821.png 1341848202.258904 depth/1341848202.258904.png
1341848202.290806 rgb/1341848202.290806.png 1341848202.290921 depth/1341848202.290921.png
1341848202.323052 rgb/1341848202.323052.png 1341848202.323077 depth/1341848202.323077.png
1341848202.358798 rgb/1341848202.358798.png 1341848202.358824 depth/1341848202.358824.png
1341848202.390884 rgb/1341848202.390884.png 1341848202.390920 depth/1341848202.390920.png
1341848202.422976 rgb/1341848202.422976.png 1341848202.423020 depth/1341848202.423020.png
1341848202.458794 rgb/1341848202.458794.png 1341848202.458819 depth/1341848202.458819.png
1341848202.490890 rgb/1341848202.490890.png 1341848202.490908 depth/1341848202.490908.png
1341848202.527956 rgb/1341848202.527956.png 1341848202.528062 depth/1341848202.528062.png
1341848202.559000 rgb/1341848202.559000.png 1341848202.559019 depth/1341848202.559019.png
1341848202.590808 rgb/1341848202.590808.png 1341848202.590823 depth/1341848202.590823.png
1341848202.626957 rgb/1341848202.626957.png 1341848202.626976 depth/1341848202.626976.png
1341848202.658732 rgb/1341848202.658732.png 1341848202.658806 depth/1341848202.658806.png
1341848202.690857 rgb/1341848202.690857.png 1341848202.690912 depth/1341848202.690912.png
1341848202.727063 rgb/1341848202.727063.png 1341848202.727101 depth/1341848202.727101.png
1341848202.759257 rgb/1341848202.759257.png 1341848202.759314 depth/1341848202.759314.png
1341848202.794861 rgb/1341848202.794861.png 1341848202.794885 depth/1341848202.794885.png
1341848202.827308 rgb/1341848202.827308.png 1341848202.827331 depth/1341848202.827331.png
1341848202.858837 rgb/1341848202.858837.png 1341848202.858872 depth/1341848202.858872.png
1341848202.894805 rgb/1341848202.894805.png 1341848202.894846 depth/1341848202.894846.png
1341848202.926976 rgb/1341848202.926976.png 1341848202.927045 depth/1341848202.927045.png
1341848202.962823 rgb/1341848202.962823.png 1341848202.962852 depth/1341848202.962852.png
1341848202.994916 rgb/1341848202.994916.png 1341848202.994941 depth/1341848202.994941.png
1341848203.026981 rgb/1341848203.026981.png 1341848203.027004 depth/1341848203.027004.png
1341848203.062849 rgb/1341848203.062849.png 1341848203.062864 depth/1341848203.062864.png
1341848203.094943 rgb/1341848203.094943.png 1341848203.094965 depth/1341848203.094965.png
1341848203.127348 rgb/1341848203.127348.png 1341848203.127363 depth/1341848203.127363.png
1341848203.162838 rgb/1341848203.162838.png 1341848203.162900 depth/1341848203.162900.png
1341848203.194762 rgb/1341848203.194762.png 1341848203.194773 depth/1341848203.194773.png
1341848203.230862 rgb/1341848203.230862.png 1341848203.230876 depth/1341848203.230876.png
1341848203.262755 rgb/1341848203.262755.png 1341848203.262779 depth/1341848203.262779.png
1341848203.294800 rgb/1341848203.294800.png 1341848203.294873 depth/1341848203.294873.png
1341848203.330838 rgb/1341848203.330838.png 1341848203.330873 depth/1341848203.330873.png
1341848203.363119 rgb/1341848203.363119.png 1341848203.363135 depth/1341848203.363135.png
1341848203.395223 rgb/1341848203.395223.png 1341848203.396045 depth/1341848203.396045.png
1341848203.435503 rgb/1341848203.435503.png 1341848203.430832 depth/1341848203.430832.png
1341848203.498825 rgb/1341848203.498825.png 1341848203.498884 depth/1341848203.498884.png
1341848203.531286 rgb/1341848203.531286.png 1341848203.532016 depth/1341848203.532016.png
1341848203.563024 rgb/1341848203.563024.png 1341848203.563047 depth/1341848203.563047.png
1341848203.599942 rgb/1341848203.599942.png 1341848203.599988 depth/1341848203.599988.png
1341848203.630868 rgb/1341848203.630868.png 1341848203.630940 depth/1341848203.630940.png
1341848203.662873 rgb/1341848203.662873.png 1341848203.662890 depth/1341848203.662890.png
1341848203.698839 rgb/1341848203.698839.png 1341848203.698851 depth/1341848203.698851.png
1341848203.730862 rgb/1341848203.730862.png 1341848203.730932 depth/1341848203.730932.png
1341848203.766867 rgb/1341848203.766867.png 1341848203.766884 depth/1341848203.766884.png
1341848203.798920 rgb/1341848203.798920.png 1341848203.798930 depth/1341848203.798930.png
1341848203.835107 rgb/1341848203.835107.png 1341848203.835956 depth/1341848203.835956.png
1341848203.867999 rgb/1341848203.867999.png 1341848203.869381 depth/1341848203.869381.png
1341848203.898920 rgb/1341848203.898920.png 1341848203.899716 depth/1341848203.899716.png
1341848203.931259 rgb/1341848203.931259.png 1341848203.932270 depth/1341848203.932270.png
1341848203.967473 rgb/1341848203.967473.png 1341848203.967788 depth/1341848203.967788.png
1341848204.035216 rgb/1341848204.035216.png 1341848204.035979 depth/1341848204.035979.png
1341848204.066826 rgb/1341848204.066826.png 1341848204.066883 depth/1341848204.066883.png
1341848204.099256 rgb/1341848204.099256.png 1341848204.099290 depth/1341848204.099290.png
1341848204.134726 rgb/1341848204.134726.png 1341848204.134739 depth/1341848204.134739.png
1341848204.166964 rgb/1341848204.166964.png 1341848204.167008 depth/1341848204.167008.png
1341848204.202902 rgb/1341848204.202902.png 1341848204.202930 depth/1341848204.202930.png
1341848204.234953 rgb/1341848204.234953.png 1341848204.235015 depth/1341848204.235015.png
1341848204.266735 rgb/1341848204.266735.png 1341848204.266763 depth/1341848204.266763.png
1341848204.302722 rgb/1341848204.302722.png 1341848204.302871 depth/1341848204.302871.png
1341848204.334816 rgb/1341848204.334816.png 1341848204.335341 depth/1341848204.335341.png
1341848204.366799 rgb/1341848204.366799.png 1341848204.366903 depth/1341848204.366903.png
1341848204.402796 rgb/1341848204.402796.png 1341848204.402811 depth/1341848204.402811.png
1341848204.434801 rgb/1341848204.434801.png 1341848204.435570 depth/1341848204.435570.png
1341848204.470726 rgb/1341848204.470726.png 1341848204.470791 depth/1341848204.470791.png
1341848204.502770 rgb/1341848204.502770.png 1341848204.502793 depth/1341848204.502793.png
1341848204.534968 rgb/1341848204.534968.png 1341848204.535532 depth/1341848204.535532.png
1341848204.570786 rgb/1341848204.570786.png 1341848204.570798 depth/1341848204.570798.png
1341848204.602873 rgb/1341848204.602873.png 1341848204.602896 depth/1341848204.602896.png
1341848204.634840 rgb/1341848204.634840.png 1341848204.635309 depth/1341848204.635309.png
1341848204.671026 rgb/1341848204.671026.png 1341848204.671038 depth/1341848204.671038.png
1341848204.702840 rgb/1341848204.702840.png 1341848204.702847 depth/1341848204.702847.png
1341848204.738730 rgb/1341848204.738730.png 1341848204.738744 depth/1341848204.738744.png
1341848204.770802 rgb/1341848204.770802.png 1341848204.770834 depth/1341848204.770834.png
1341848204.802797 rgb/1341848204.802797.png 1341848204.802810 depth/1341848204.802810.png
1341848204.838789 rgb/1341848204.838789.png 1341848204.838866 depth/1341848204.838866.png
1341848204.870853 rgb/1341848204.870853.png 1341848204.870865 depth/1341848204.870865.png
1341848204.902767 rgb/1341848204.902767.png 1341848204.902790 depth/1341848204.902790.png
1341848204.938770 rgb/1341848204.938770.png 1341848204.938847 depth/1341848204.938847.png
1341848204.970814 rgb/1341848204.970814.png 1341848204.970830 depth/1341848204.970830.png
1341848205.006746 rgb/1341848205.006746.png 1341848205.006760 depth/1341848205.006760.png
1341848205.038844 rgb/1341848205.038844.png 1341848205.038858 depth/1341848205.038858.png
1341848205.070913 rgb/1341848205.070913.png 1341848205.070928 depth/1341848205.070928.png
1341848205.106820 rgb/1341848205.106820.png 1341848205.107360 depth/1341848205.107360.png
1341848205.138855 rgb/1341848205.138855.png 1341848205.138873 depth/1341848205.138873.png
1341848205.174813 rgb/1341848205.174813.png 1341848205.174832 depth/1341848205.174832.png
1341848205.239001 rgb/1341848205.239001.png 1341848205.239024 depth/1341848205.239024.png
1341848205.274873 rgb/1341848205.274873.png 1341848205.274888 depth/1341848205.274888.png
1341848205.306822 rgb/1341848205.306822.png 1341848205.306841 depth/1341848205.306841.png
1341848205.338786 rgb/1341848205.338786.png 1341848205.338823 depth/1341848205.338823.png
1341848205.374979 rgb/1341848205.374979.png 1341848205.375021 depth/1341848205.375021.png
1341848205.406768 rgb/1341848205.406768.png 1341848205.406782 depth/1341848205.406782.png
1341848205.442724 rgb/1341848205.442724.png 1341848205.442742 depth/1341848205.442742.png
1341848205.474875 rgb/1341848205.474875.png 1341848205.474899 depth/1341848205.474899.png
1341848205.506916 rgb/1341848205.506916.png 1341848205.506938 depth/1341848205.506938.png
1341848205.542797 rgb/1341848205.542797.png 1341848205.542837 depth/1341848205.542837.png
1341848205.574904 rgb/1341848205.574904.png 1341848205.574916 depth/1341848205.574916.png
1341848205.606749 rgb/1341848205.606749.png 1341848205.606768 depth/1341848205.606768.png
1341848205.643275 rgb/1341848205.643275.png 1341848205.643289 depth/1341848205.643289.png
1341848205.674856 rgb/1341848205.674856.png 1341848205.674927 depth/1341848205.674927.png
1341848205.710891 rgb/1341848205.710891.png 1341848205.710917 depth/1341848205.710917.png
1341848205.742764 rgb/1341848205.742764.png 1341848205.742781 depth/1341848205.742781.png
1341848205.774836 rgb/1341848205.774836.png 1341848205.774849 depth/1341848205.774849.png
1341848205.810716 rgb/1341848205.810716.png 1341848205.810730 depth/1341848205.810730.png
1341848205.843832 rgb/1341848205.843832.png 1341848205.843958 depth/1341848205.843958.png
1341848205.874985 rgb/1341848205.874985.png 1341848205.875008 depth/1341848205.875008.png
1341848205.910826 rgb/1341848205.910826.png 1341848205.910859 depth/1341848205.910859.png
1341848205.943117 rgb/1341848205.943117.png 1341848205.943139 depth/1341848205.943139.png
1341848205.978925 rgb/1341848205.978925.png 1341848205.978941 depth/1341848205.978941.png
1341848206.010747 rgb/1341848206.010747.png 1341848206.010823 depth/1341848206.010823.png
1341848206.042866 rgb/1341848206.042866.png 1341848206.042895 depth/1341848206.042895.png
1341848206.078773 rgb/1341848206.078773.png 1341848206.078787 depth/1341848206.078787.png
1341848206.110785 rgb/1341848206.110785.png 1341848206.110828 depth/1341848206.110828.png
1341848206.142784 rgb/1341848206.142784.png 1341848206.143837 depth/1341848206.143837.png
1341848206.178877 rgb/1341848206.178877.png 1341848206.178893 depth/1341848206.178893.png
1341848206.210888 rgb/1341848206.210888.png 1341848206.210951 depth/1341848206.210951.png
1341848206.246920 rgb/1341848206.246920.png 1341848206.246930 depth/1341848206.246930.png
1341848206.278950 rgb/1341848206.278950.png 1341848206.278987 depth/1341848206.278987.png
1341848206.310818 rgb/1341848206.310818.png 1341848206.310858 depth/1341848206.310858.png
1341848206.346854 rgb/1341848206.346854.png 1341848206.346872 depth/1341848206.346872.png
1341848206.378885 rgb/1341848206.378885.png 1341848206.378899 depth/1341848206.378899.png
1341848206.414812 rgb/1341848206.414812.png 1341848206.414825 depth/1341848206.414825.png
1341848206.446940 rgb/1341848206.446940.png 1341848206.446954 depth/1341848206.446954.png
1341848206.478764 rgb/1341848206.478764.png 1341848206.478778 depth/1341848206.478778.png
1341848206.514805 rgb/1341848206.514805.png 1341848206.514860 depth/1341848206.514860.png
1341848206.547068 rgb/1341848206.547068.png 1341848206.547082 depth/1341848206.547082.png
1341848206.579009 rgb/1341848206.579009.png 1341848206.579027 depth/1341848206.579027.png
1341848206.614753 rgb/1341848206.614753.png 1341848206.614793 depth/1341848206.614793.png
1341848206.646842 rgb/1341848206.646842.png 1341848206.646885 depth/1341848206.646885.png
1341848206.683961 rgb/1341848206.683961.png 1341848206.684046 depth/1341848206.684046.png
1341848206.714758 rgb/1341848206.714758.png 1341848206.714771 depth/1341848206.714771.png
1341848206.746907 rgb/1341848206.746907.png 1341848206.747660 depth/1341848206.747660.png
1341848206.782729 rgb/1341848206.782729.png 1341848206.782755 depth/1341848206.782755.png
1341848206.814753 rgb/1341848206.814753.png 1341848206.814763 depth/1341848206.814763.png
1341848206.846915 rgb/1341848206.846915.png 1341848206.846937 depth/1341848206.846937.png
1341848206.882764 rgb/1341848206.882764.png 1341848206.882796 depth/1341848206.882796.png
1341848206.914855 rgb/1341848206.914855.png 1341848206.915910 depth/1341848206.915910.png
1341848206.950792 rgb/1341848206.950792.png 1341848206.950802 depth/1341848206.950802.png
1341848206.982816 rgb/1341848206.982816.png 1341848206.982828 depth/1341848206.982828.png
1341848207.014911 rgb/1341848207.014911.png 1341848207.014931 depth/1341848207.014931.png
1341848207.050874 rgb/1341848207.050874.png 1341848207.050902 depth/1341848207.050902.png
1341848207.082850 rgb/1341848207.082850.png 1341848207.082908 depth/1341848207.082908.png
1341848207.114753 rgb/1341848207.114753.png 1341848207.114765 depth/1341848207.114765.png
1341848207.151179 rgb/1341848207.151179.png 1341848207.151192 depth/1341848207.151192.png
1341848207.182860 rgb/1341848207.182860.png 1341848207.182875 depth/1341848207.182875.png
1341848207.218750 rgb/1341848207.218750.png 1341848207.218764 depth/1341848207.218764.png
1341848207.250977 rgb/1341848207.250977.png 1341848207.251735 depth/1341848207.251735.png
1341848207.282786 rgb/1341848207.282786.png 1341848207.282799 depth/1341848207.282799.png
1341848207.318903 rgb/1341848207.318903.png 1341848207.318914 depth/1341848207.318914.png
1341848207.350844 rgb/1341848207.350844.png 1341848207.350857 depth/1341848207.350857.png
1341848207.386806 rgb/1341848207.386806.png 1341848207.386818 depth/1341848207.386818.png
1341848207.418811 rgb/1341848207.418811.png 1341848207.418822 depth/1341848207.418822.png
1341848207.451051 rgb/1341848207.451051.png 1341848207.451065 depth/1341848207.451065.png
1341848207.486815 rgb/1341848207.486815.png 1341848207.486828 depth/1341848207.486828.png
1341848207.519015 rgb/1341848207.519015.png 1341848207.519030 depth/1341848207.519030.png
1341848207.550807 rgb/1341848207.550807.png 1341848207.550816 depth/1341848207.550816.png
1341848207.586953 rgb/1341848207.586953.png 1341848207.586984 depth/1341848207.586984.png
1341848207.618933 rgb/1341848207.618933.png 1341848207.618946 depth/1341848207.618946.png
1341848207.654944 rgb/1341848207.654944.png 1341848207.654965 depth/1341848207.654965.png
1341848207.693876 rgb/1341848207.693876.png 1341848207.693916 depth/1341848207.693916.png
1341848207.754914 rgb/1341848207.754914.png 1341848207.754934 depth/1341848207.754934.png
1341848207.786813 rgb/1341848207.786813.png 1341848207.786830 depth/1341848207.786830.png
1341848207.818837 rgb/1341848207.818837.png 1341848207.818853 depth/1341848207.818853.png
1341848207.854788 rgb/1341848207.854788.png 1341848207.854820 depth/1341848207.854820.png
1341848207.886770 rgb/1341848207.886770.png 1341848207.886784 depth/1341848207.886784.png
1341848207.922756 rgb/1341848207.922756.png 1341848207.922778 depth/1341848207.922778.png
1341848207.954773 rgb/1341848207.954773.png 1341848207.954798 depth/1341848207.954798.png
1341848207.986759 rgb/1341848207.986759.png 1341848207.986780 depth/1341848207.986780.png
1341848208.022857 rgb/1341848208.022857.png 1341848208.022871 depth/1341848208.022871.png
1341848208.054843 rgb/1341848208.054843.png 1341848208.054859 depth/1341848208.054859.png
1341848208.087087 rgb/1341848208.087087.png 1341848208.087137 depth/1341848208.087137.png
1341848208.122770 rgb/1341848208.122770.png 1341848208.122785 depth/1341848208.122785.png
1341848208.154784 rgb/1341848208.154784.png 1341848208.154809 depth/1341848208.154809.png
1341848208.191030 rgb/1341848208.191030.png 1341848208.191058 depth/1341848208.191058.png
1341848208.222799 rgb/1341848208.222799.png 1341848208.222825 depth/1341848208.222825.png
1341848208.254896 rgb/1341848208.254896.png 1341848208.254909 depth/1341848208.254909.png
1341848208.290793 rgb/1341848208.290793.png 1341848208.290810 depth/1341848208.290810.png
1341848208.322950 rgb/1341848208.322950.png 1341848208.322995 depth/1341848208.322995.png
1341848208.355053 rgb/1341848208.355053.png 1341848208.355076 depth/1341848208.355076.png
1341848208.391112 rgb/1341848208.391112.png 1341848208.391168 depth/1341848208.391168.png
1341848208.422893 rgb/1341848208.422893.png 1341848208.422935 depth/1341848208.422935.png
1341848208.459106 rgb/1341848208.459106.png 1341848208.459137 depth/1341848208.459137.png
1341848208.490773 rgb/1341848208.490773.png 1341848208.490798 depth/1341848208.490798.png
1341848208.522880 rgb/1341848208.522880.png 1341848208.522897 depth/1341848208.522897.png
1341848208.558812 rgb/1341848208.558812.png 1341848208.558839 depth/1341848208.558839.png
1341848208.590795 rgb/1341848208.590795.png 1341848208.590815 depth/1341848208.590815.png
1341848208.626964 rgb/1341848208.626964.png 1341848208.626980 depth/1341848208.626980.png
1341848208.658813 rgb/1341848208.658813.png 1341848208.658841 depth/1341848208.658841.png
1341848208.690807 rgb/1341848208.690807.png 1341848208.690821 depth/1341848208.690821.png
1341848208.726943 rgb/1341848208.726943.png 1341848208.726977 depth/1341848208.726977.png
1341848208.758836 rgb/1341848208.758836.png 1341848208.758856 depth/1341848208.758856.png
1341848208.790869 rgb/1341848208.790869.png 1341848208.790881 depth/1341848208.790881.png
1341848208.827291 rgb/1341848208.827291.png 1341848208.827308 depth/1341848208.827308.png
1341848208.858848 rgb/1341848208.858848.png 1341848208.858865 depth/1341848208.858865.png
1341848208.894724 rgb/1341848208.894724.png 1341848208.894743 depth/1341848208.894743.png
1341848208.926819 rgb/1341848208.926819.png 1341848208.927423 depth/1341848208.927423.png
1341848208.958803 rgb/1341848208.958803.png 1341848208.958861 depth/1341848208.958861.png
1341848208.994719 rgb/1341848208.994719.png 1341848208.994731 depth/1341848208.994731.png
1341848209.026833 rgb/1341848209.026833.png 1341848209.027117 depth/1341848209.027117.png
1341848209.058797 rgb/1341848209.058797.png 1341848209.058865 depth/1341848209.058865.png
1341848209.094825 rgb/1341848209.094825.png 1341848209.094836 depth/1341848209.094836.png
1341848209.162935 rgb/1341848209.162935.png 1341848209.163676 depth/1341848209.163676.png
1341848209.195294 rgb/1341848209.195294.png 1341848209.195307 depth/1341848209.195307.png
1341848209.226887 rgb/1341848209.226887.png 1341848209.226905 depth/1341848209.226905.png
1341848209.262855 rgb/1341848209.262855.png 1341848209.262893 depth/1341848209.262893.png
1341848209.294888 rgb/1341848209.294888.png 1341848209.294922 depth/1341848209.294922.png
1341848209.326952 rgb/1341848209.326952.png 1341848209.326974 depth/1341848209.326974.png
1341848209.362989 rgb/1341848209.362989.png 1341848209.363010 depth/1341848209.363010.png
1341848209.394782 rgb/1341848209.394782.png 1341848209.394840 depth/1341848209.394840.png
1341848209.430842 rgb/1341848209.430842.png 1341848209.430858 depth/1341848209.430858.png
1341848209.462783 rgb/1341848209.462783.png 1341848209.462824 depth/1341848209.462824.png
1341848209.494894 rgb/1341848209.494894.png 1341848209.494932 depth/1341848209.494932.png
1341848209.530945 rgb/1341848209.530945.png 1341848209.530970 depth/1341848209.530970.png
1341848209.562786 rgb/1341848209.562786.png 1341848209.562831 depth/1341848209.562831.png
1341848209.598748 rgb/1341848209.598748.png 1341848209.598794 depth/1341848209.598794.png
1341848209.630868 rgb/1341848209.630868.png 1341848209.630885 depth/1341848209.630885.png
1341848209.662770 rgb/1341848209.662770.png 1341848209.662803 depth/1341848209.662803.png
1341848209.698805 rgb/1341848209.698805.png 1341848209.698818 depth/1341848209.698818.png
1341848209.731004 rgb/1341848209.731004.png 1341848209.731698 depth/1341848209.731698.png
1341848209.762808 rgb/1341848209.762808.png 1341848209.762866 depth/1341848209.762866.png
1341848209.798881 rgb/1341848209.798881.png 1341848209.798924 depth/1341848209.798924.png
1341848209.830869 rgb/1341848209.830869.png 1341848209.830918 depth/1341848209.830918.png
1341848209.866786 rgb/1341848209.866786.png 1341848209.866834 depth/1341848209.866834.png
1341848209.898843 rgb/1341848209.898843.png 1341848209.898863 depth/1341848209.898863.png
1341848209.931472 rgb/1341848209.931472.png 1341848209.931555 depth/1341848209.931555.png
1341848209.967052 rgb/1341848209.967052.png 1341848209.967401 depth/1341848209.967401.png
1341848210.003771 rgb/1341848210.003771.png 1341848210.003812 depth/1341848210.003812.png
1341848210.031963 rgb/1341848210.031963.png 1341848210.032040 depth/1341848210.032040.png
1341848210.067579 rgb/1341848210.067579.png 1341848210.068297 depth/1341848210.068297.png
1341848210.102321 rgb/1341848210.102321.png 1341848210.108395 depth/1341848210.108395.png
1341848210.138041 rgb/1341848210.138041.png 1341848210.138995 depth/1341848210.138995.png
1341848210.172181 rgb/1341848210.172181.png 1341848210.172261 depth/1341848210.172261.png
1341848210.209174 rgb/1341848210.209174.png 1341848210.217091 depth/1341848210.217091.png
1341848210.238298 rgb/1341848210.238298.png 1341848210.238662 depth/1341848210.238662.png
1341848210.274290 rgb/1341848210.274290.png 1341848210.274937 depth/1341848210.274937.png
1341848210.307426 rgb/1341848210.307426.png 1341848210.307492 depth/1341848210.307492.png
1341848210.338442 rgb/1341848210.338442.png 1341848210.339898 depth/1341848210.339898.png
1341848210.403043 rgb/1341848210.403043.png 1341848210.403569 depth/1341848210.403569.png
1341848210.436478 rgb/1341848210.436478.png 1341848210.440806 depth/1341848210.440806.png
1341848210.474263 rgb/1341848210.474263.png 1341848210.475626 depth/1341848210.475626.png
1341848210.506624 rgb/1341848210.506624.png 1341848210.507478 depth/1341848210.507478.png
1341848210.541761 rgb/1341848210.541761.png 1341848210.542250 depth/1341848210.542250.png
1341848210.574007 rgb/1341848210.574007.png 1341848210.574024 depth/1341848210.574024.png
1341848210.605766 rgb/1341848210.605766.png 1341848210.605790 depth/1341848210.605790.png
1341848210.641757 rgb/1341848210.641757.png 1341848210.641783 depth/1341848210.641783.png
1341848210.673768 rgb/1341848210.673768.png 1341848210.673812 depth/1341848210.673812.png
1341848210.709860 rgb/1341848210.709860.png 1341848210.709896 depth/1341848210.709896.png
1341848210.773876 rgb/1341848210.773876.png 1341848210.773991 depth/1341848210.773991.png
1341848210.838937 rgb/1341848210.838937.png 1341848210.838975 depth/1341848210.838975.png
1341848210.870699 rgb/1341848210.870699.png 1341848210.870734 depth/1341848210.870734.png
1341848210.902766 rgb/1341848210.902766.png 1341848210.902802 depth/1341848210.902802.png
1341848210.938769 rgb/1341848210.938769.png 1341848210.938796 depth/1341848210.938796.png
1341848210.970724 rgb/1341848210.970724.png 1341848210.970745 depth/1341848210.970745.png
1341848211.038937 rgb/1341848211.038937.png 1341848211.038953 depth/1341848211.038953.png
1341848211.070785 rgb/1341848211.070785.png 1341848211.070827 depth/1341848211.070827.png
1341848211.106809 rgb/1341848211.106809.png 1341848211.106826 depth/1341848211.106826.png
1341848211.139333 rgb/1341848211.139333.png 1341848211.139351 depth/1341848211.139351.png
1341848211.171017 rgb/1341848211.171017.png 1341848211.171046 depth/1341848211.171046.png
1341848211.206782 rgb/1341848211.206782.png 1341848211.206799 depth/1341848211.206799.png
1341848211.238842 rgb/1341848211.238842.png 1341848211.238857 depth/1341848211.238857.png
1341848211.270819 rgb/1341848211.270819.png 1341848211.271133 depth/1341848211.271133.png
1341848211.313914 rgb/1341848211.313914.png 1341848211.313931 depth/1341848211.313931.png
1341848211.346117 rgb/1341848211.346117.png 1341848211.346244 depth/1341848211.346244.png
1341848211.381752 rgb/1341848211.381752.png 1341848211.381762 depth/1341848211.381762.png
1341848211.413916 rgb/1341848211.413916.png 1341848211.414351 depth/1341848211.414351.png
1341848211.445812 rgb/1341848211.445812.png 1341848211.445835 depth/1341848211.445835.png
1341848211.481789 rgb/1341848211.481789.png 1341848211.482472 depth/1341848211.482472.png
1341848211.514689 rgb/1341848211.514689.png 1341848211.514719 depth/1341848211.514719.png
1341848211.545851 rgb/1341848211.545851.png 1341848211.545864 depth/1341848211.545864.png
1341848211.581802 rgb/1341848211.581802.png 1341848211.581825 depth/1341848211.581825.png
1341848211.613889 rgb/1341848211.613889.png 1341848211.613999 depth/1341848211.613999.png
1341848211.650666 rgb/1341848211.650666.png 1341848211.651256 depth/1341848211.651256.png
1341848211.681813 rgb/1341848211.681813.png 1341848211.681829 depth/1341848211.681829.png
1341848211.713870 rgb/1341848211.713870.png 1341848211.713890 depth/1341848211.713890.png
1341848211.774927 rgb/1341848211.774927.png 1341848211.774948 depth/1341848211.774948.png
1341848211.810787 rgb/1341848211.810787.png 1341848211.810814 depth/1341848211.810814.png
1341848211.842927 rgb/1341848211.842927.png 1341848211.842962 depth/1341848211.842962.png
1341848211.874782 rgb/1341848211.874782.png 1341848211.874811 depth/1341848211.874811.png
1341848211.911279 rgb/1341848211.911279.png 1341848211.911474 depth/1341848211.911474.png
1341848211.943008 rgb/1341848211.943008.png 1341848211.943032 depth/1341848211.943032.png
1341848211.974782 rgb/1341848211.974782.png 1341848211.974819 depth/1341848211.974819.png
1341848212.010761 rgb/1341848212.010761.png 1341848212.010787 depth/1341848212.010787.png
1341848212.042882 rgb/1341848212.042882.png 1341848212.043339 depth/1341848212.043339.png
1341848212.078895 rgb/1341848212.078895.png 1341848212.078909 depth/1341848212.078909.png
1341848212.110797 rgb/1341848212.110797.png 1341848212.110831 depth/1341848212.110831.png
1341848212.143290 rgb/1341848212.143290.png 1341848212.143341 depth/1341848212.143341.png
1341848212.178822 rgb/1341848212.178822.png 1341848212.178842 depth/1341848212.178842.png
1341848212.210820 rgb/1341848212.210820.png 1341848212.210835 depth/1341848212.210835.png
1341848212.243238 rgb/1341848212.243238.png 1341848212.243262 depth/1341848212.243262.png
1341848212.278862 rgb/1341848212.278862.png 1341848212.278880 depth/1341848212.278880.png
1341848212.310903 rgb/1341848212.310903.png 1341848212.310912 depth/1341848212.310912.png
1341848212.346897 rgb/1341848212.346897.png 1341848212.346982 depth/1341848212.346982.png
1341848212.378789 rgb/1341848212.378789.png 1341848212.378808 depth/1341848212.378808.png
1341848212.410789 rgb/1341848212.410789.png 1341848212.410808 depth/1341848212.410808.png
1341848212.446830 rgb/1341848212.446830.png 1341848212.446847 depth/1341848212.446847.png
1341848212.478950 rgb/1341848212.478950.png 1341848212.478981 depth/1341848212.478981.png
1341848212.510887 rgb/1341848212.510887.png 1341848212.511353 depth/1341848212.511353.png
1341848212.546852 rgb/1341848212.546852.png 1341848212.546927 depth/1341848212.546927.png
1341848212.578830 rgb/1341848212.578830.png 1341848212.578847 depth/1341848212.578847.png
1341848212.614874 rgb/1341848212.614874.png 1341848212.614897 depth/1341848212.614897.png
1341848212.646838 rgb/1341848212.646838.png 1341848212.646860 depth/1341848212.646860.png
1341848212.679120 rgb/1341848212.679120.png 1341848212.679132 depth/1341848212.679132.png
1341848212.714943 rgb/1341848212.714943.png 1341848212.714958 depth/1341848212.714958.png
1341848212.746794 rgb/1341848212.746794.png 1341848212.746811 depth/1341848212.746811.png
1341848212.778907 rgb/1341848212.778907.png 1341848212.779527 depth/1341848212.779527.png
1341848212.814843 rgb/1341848212.814843.png 1341848212.815401 depth/1341848212.815401.png
1341848212.846722 rgb/1341848212.846722.png 1341848212.846746 depth/1341848212.846746.png
1341848212.882962 rgb/1341848212.882962.png 1341848212.882993 depth/1341848212.882993.png
1341848212.914749 rgb/1341848212.914749.png 1341848212.914775 depth/1341848212.914775.png
1341848212.946917 rgb/1341848212.946917.png 1341848212.946935 depth/1341848212.946935.png
1341848212.982747 rgb/1341848212.982747.png 1341848212.982764 depth/1341848212.982764.png
1341848213.014970 rgb/1341848213.014970.png 1341848213.015817 depth/1341848213.015817.png
1341848213.050796 rgb/1341848213.050796.png 1341848213.050829 depth/1341848213.050829.png
1341848213.082844 rgb/1341848213.082844.png 1341848213.082859 depth/1341848213.082859.png
1341848213.114799 rgb/1341848213.114799.png 1341848213.114839 depth/1341848213.114839.png
1341848213.150876 rgb/1341848213.150876.png 1341848213.150904 depth/1341848213.150904.png
1341848213.182773 rgb/1341848213.182773.png 1341848213.183237 depth/1341848213.183237.png
1341848213.215230 rgb/1341848213.215230.png 1341848213.215272 depth/1341848213.215272.png
1341848213.250798 rgb/1341848213.250798.png 1341848213.250937 depth/1341848213.250937.png
1341848213.282831 rgb/1341848213.282831.png 1341848213.282888 depth/1341848213.282888.png
1341848213.318903 rgb/1341848213.318903.png 1341848213.318917 depth/1341848213.318917.png
1341848213.350973 rgb/1341848213.350973.png 1341848213.351036 depth/1341848213.351036.png
1341848213.382899 rgb/1341848213.382899.png 1341848213.382915 depth/1341848213.382915.png
1341848213.418794 rgb/1341848213.418794.png 1341848213.418810 depth/1341848213.418810.png
1341848213.450857 rgb/1341848213.450857.png 1341848213.450885 depth/1341848213.450885.png
1341848213.482824 rgb/1341848213.482824.png 1341848213.482849 depth/1341848213.482849.png
1341848213.518891 rgb/1341848213.518891.png 1341848213.518929 depth/1341848213.518929.png
1341848213.550818 rgb/1341848213.550818.png 1341848213.550848 depth/1341848213.550848.png
1341848213.586780 rgb/1341848213.586780.png 1341848213.586795 depth/1341848213.586795.png
1341848213.618796 rgb/1341848213.618796.png 1341848213.619419 depth/1341848213.619419.png
1341848213.650827 rgb/1341848213.650827.png 1341848213.650878 depth/1341848213.650878.png
1341848213.686919 rgb/1341848213.686919.png 1341848213.686932 depth/1341848213.686932.png
1341848213.718737 rgb/1341848213.718737.png 1341848213.718748 depth/1341848213.718748.png
1341848213.750832 rgb/1341848213.750832.png 1341848213.750866 depth/1341848213.750866.png
1341848213.786834 rgb/1341848213.786834.png 1341848213.786849 depth/1341848213.786849.png
1341848213.818808 rgb/1341848213.818808.png 1341848213.818819 depth/1341848213.818819.png
1341848213.854821 rgb/1341848213.854821.png 1341848213.854851 depth/1341848213.854851.png
1341848213.886752 rgb/1341848213.886752.png 1341848213.886769 depth/1341848213.886769.png
1341848213.918782 rgb/1341848213.918782.png 1341848213.918799 depth/1341848213.918799.png
1341848213.954808 rgb/1341848213.954808.png 1341848213.954842 depth/1341848213.954842.png
1341848213.986946 rgb/1341848213.986946.png 1341848213.986960 depth/1341848213.986960.png
1341848214.022908 rgb/1341848214.022908.png 1341848214.022937 depth/1341848214.022937.png
1341848214.054738 rgb/1341848214.054738.png 1341848214.054751 depth/1341848214.054751.png
1341848214.086822 rgb/1341848214.086822.png 1341848214.086836 depth/1341848214.086836.png
1341848214.122796 rgb/1341848214.122796.png 1341848214.122895 depth/1341848214.122895.png
1341848214.155572 rgb/1341848214.155572.png 1341848214.155596 depth/1341848214.155596.png
1341848214.186946 rgb/1341848214.186946.png 1341848214.186973 depth/1341848214.186973.png
1341848214.222928 rgb/1341848214.222928.png 1341848214.222940 depth/1341848214.222940.png
1341848214.254825 rgb/1341848214.254825.png 1341848214.254888 depth/1341848214.254888.png
1341848214.290826 rgb/1341848214.290826.png 1341848214.290844 depth/1341848214.290844.png
1341848214.322922 rgb/1341848214.322922.png 1341848214.322957 depth/1341848214.322957.png
1341848214.354840 rgb/1341848214.354840.png 1341848214.354957 depth/1341848214.354957.png
1341848214.390756 rgb/1341848214.390756.png 1341848214.390780 depth/1341848214.390780.png
1341848214.422953 rgb/1341848214.422953.png 1341848214.422985 depth/1341848214.422985.png
1341848214.454847 rgb/1341848214.454847.png 1341848214.454876 depth/1341848214.454876.png
1341848214.490830 rgb/1341848214.490830.png 1341848214.490909 depth/1341848214.490909.png
1341848214.558867 rgb/1341848214.558867.png 1341848214.558981 depth/1341848214.558981.png
1341848214.590862 rgb/1341848214.590862.png 1341848214.591469 depth/1341848214.591469.png
1341848214.622826 rgb/1341848214.622826.png 1341848214.622919 depth/1341848214.622919.png
1341848214.658800 rgb/1341848214.658800.png 1341848214.658827 depth/1341848214.658827.png
1341848214.690796 rgb/1341848214.690796.png 1341848214.690912 depth/1341848214.690912.png
1341848214.722796 rgb/1341848214.722796.png 1341848214.722809 depth/1341848214.722809.png
1341848214.758809 rgb/1341848214.758809.png 1341848214.758826 depth/1341848214.758826.png
1341848214.790836 rgb/1341848214.790836.png 1341848214.791334 depth/1341848214.791334.png
1341848214.826844 rgb/1341848214.826844.png 1341848214.826879 depth/1341848214.826879.png
1341848214.858895 rgb/1341848214.858895.png 1341848214.858940 depth/1341848214.858940.png
1341848214.890772 rgb/1341848214.890772.png 1341848214.890796 depth/1341848214.890796.png
1341848214.926851 rgb/1341848214.926851.png 1341848214.926862 depth/1341848214.926862.png
1341848214.958848 rgb/1341848214.958848.png 1341848214.959364 depth/1341848214.959364.png
1341848214.990815 rgb/1341848214.990815.png 1341848214.990842 depth/1341848214.990842.png
1341848215.027790 rgb/1341848215.027790.png 1341848215.027810 depth/1341848215.027810.png
1341848215.058896 rgb/1341848215.058896.png 1341848215.059493 depth/1341848215.059493.png
1341848215.094867 rgb/1341848215.094867.png 1341848215.094891 depth/1341848215.094891.png
1341848215.126897 rgb/1341848215.126897.png 1341848215.126914 depth/1341848215.126914.png
1341848215.158879 rgb/1341848215.158879.png 1341848215.158909 depth/1341848215.158909.png
1341848215.194731 rgb/1341848215.194731.png 1341848215.194762 depth/1341848215.194762.png
1341848215.226807 rgb/1341848215.226807.png 1341848215.226830 depth/1341848215.226830.png
1341848215.262834 rgb/1341848215.262834.png 1341848215.262848 depth/1341848215.262848.png
1341848215.294971 rgb/1341848215.294971.png 1341848215.294988 depth/1341848215.294988.png
1341848215.326938 rgb/1341848215.326938.png 1341848215.326968 depth/1341848215.326968.png
1341848215.362851 rgb/1341848215.362851.png 1341848215.362882 depth/1341848215.362882.png
1341848215.394799 rgb/1341848215.394799.png 1341848215.394802 depth/1341848215.394802.png
1341848215.426934 rgb/1341848215.426934.png 1341848215.426950 depth/1341848215.426950.png
1341848215.462850 rgb/1341848215.462850.png 1341848215.462882 depth/1341848215.462882.png
1341848215.494878 rgb/1341848215.494878.png 1341848215.494897 depth/1341848215.494897.png
1341848215.530782 rgb/1341848215.530782.png 1341848215.530823 depth/1341848215.530823.png
1341848215.562917 rgb/1341848215.562917.png 1341848215.562930 depth/1341848215.562930.png
1341848215.594904 rgb/1341848215.594904.png 1341848215.594915 depth/1341848215.594915.png
1341848215.630836 rgb/1341848215.630836.png 1341848215.631367 depth/1341848215.631367.png
1341848215.663531 rgb/1341848215.663531.png 1341848215.663547 depth/1341848215.663547.png
1341848215.694802 rgb/1341848215.694802.png 1341848215.694826 depth/1341848215.694826.png
1341848215.730996 rgb/1341848215.730996.png 1341848215.731014 depth/1341848215.731014.png
1341848215.762861 rgb/1341848215.762861.png 1341848215.762874 depth/1341848215.762874.png
1341848215.798723 rgb/1341848215.798723.png 1341848215.798733 depth/1341848215.798733.png
1341848215.830872 rgb/1341848215.830872.png 1341848215.830900 depth/1341848215.830900.png
1341848215.862870 rgb/1341848215.862870.png 1341848215.862884 depth/1341848215.862884.png
1341848215.898871 rgb/1341848215.898871.png 1341848215.898886 depth/1341848215.898886.png
1341848215.930962 rgb/1341848215.930962.png 1341848215.931014 depth/1341848215.931014.png
1341848215.963016 rgb/1341848215.963016.png 1341848215.963070 depth/1341848215.963070.png
1341848215.998923 rgb/1341848215.998923.png 1341848215.998937 depth/1341848215.998937.png
1341848216.030907 rgb/1341848216.030907.png 1341848216.031519 depth/1341848216.031519.png
1341848216.068159 rgb/1341848216.068159.png 1341848216.068222 depth/1341848216.068222.png
1341848216.098906 rgb/1341848216.098906.png 1341848216.098927 depth/1341848216.098927.png
1341848216.131464 rgb/1341848216.131464.png 1341848216.131479 depth/1341848216.131479.png
1341848216.166777 rgb/1341848216.166777.png 1341848216.166804 depth/1341848216.166804.png
1341848216.198858 rgb/1341848216.198858.png 1341848216.198869 depth/1341848216.198869.png
1341848216.234756 rgb/1341848216.234756.png 1341848216.234771 depth/1341848216.234771.png
1341848216.266904 rgb/1341848216.266904.png 1341848216.266918 depth/1341848216.266918.png
1341848216.298954 rgb/1341848216.298954.png 1341848216.298970 depth/1341848216.298970.png
1341848216.335278 rgb/1341848216.335278.png 1341848216.335299 depth/1341848216.335299.png
1341848216.402997 rgb/1341848216.402997.png 1341848216.404203 depth/1341848216.404203.png
1341848216.436350 rgb/1341848216.436350.png 1341848216.436444 depth/1341848216.436444.png
1341848216.470540 rgb/1341848216.470540.png 1341848216.471392 depth/1341848216.471392.png
1341848216.508156 rgb/1341848216.508156.png 1341848216.509583 depth/1341848216.509583.png
1341848216.542205 rgb/1341848216.542205.png 1341848216.544395 depth/1341848216.544395.png
1341848216.577439 rgb/1341848216.577439.png 1341848216.578670 depth/1341848216.578670.png
1341848216.607600 rgb/1341848216.607600.png 1341848216.607856 depth/1341848216.607856.png
1341848216.642754 rgb/1341848216.642754.png 1341848216.643551 depth/1341848216.643551.png
1341848216.674803 rgb/1341848216.674803.png 1341848216.676560 depth/1341848216.676560.png
1341848216.706164 rgb/1341848216.706164.png 1341848216.706182 depth/1341848216.706182.png
1341848216.834914 rgb/1341848216.834914.png 1341848216.834926 depth/1341848216.834926.png
1341848216.870801 rgb/1341848216.870801.png 1341848216.870819 depth/1341848216.870819.png
1341848216.902912 rgb/1341848216.902912.png 1341848216.902934 depth/1341848216.902934.png
1341848216.941809 rgb/1341848216.941809.png 1341848216.941821 depth/1341848216.941821.png
1341848216.975203 rgb/1341848216.975203.png 1341848216.976254 depth/1341848216.976254.png
1341848217.010069 rgb/1341848217.010069.png 1341848217.010085 depth/1341848217.010085.png
1341848217.041752 rgb/1341848217.041752.png 1341848217.041769 depth/1341848217.041769.png
1341848217.073922 rgb/1341848217.073922.png 1341848217.073969 depth/1341848217.073969.png
1341848217.141773 rgb/1341848217.141773.png 1341848217.141798 depth/1341848217.141798.png
1341848217.203002 rgb/1341848217.203002.png 1341848217.203033 depth/1341848217.203033.png
1341848217.238897 rgb/1341848217.238897.png 1341848217.238908 depth/1341848217.238908.png
1341848217.271095 rgb/1341848217.271095.png 1341848217.271113 depth/1341848217.271113.png
1341848217.306916 rgb/1341848217.306916.png 1341848217.306933 depth/1341848217.306933.png
1341848217.338709 rgb/1341848217.338709.png 1341848217.338750 depth/1341848217.338750.png
1341848217.370817 rgb/1341848217.370817.png 1341848217.370896 depth/1341848217.370896.png
1341848217.406753 rgb/1341848217.406753.png 1341848217.406769 depth/1341848217.406769.png
1341848217.439299 rgb/1341848217.439299.png 1341848217.439316 depth/1341848217.439316.png
1341848217.474811 rgb/1341848217.474811.png 1341848217.474822 depth/1341848217.474822.png
1341848217.506748 rgb/1341848217.506748.png 1341848217.506774 depth/1341848217.506774.png
1341848217.538799 rgb/1341848217.538799.png 1341848217.538818 depth/1341848217.538818.png
1341848217.574892 rgb/1341848217.574892.png 1341848217.574909 depth/1341848217.574909.png
1341848217.606700 rgb/1341848217.606700.png 1341848217.606712 depth/1341848217.606712.png
1341848217.639138 rgb/1341848217.639138.png 1341848217.639159 depth/1341848217.639159.png
1341848217.674986 rgb/1341848217.674986.png 1341848217.674999 depth/1341848217.674999.png
1341848217.706806 rgb/1341848217.706806.png 1341848217.706821 depth/1341848217.706821.png
1341848217.742997 rgb/1341848217.742997.png 1341848217.743014 depth/1341848217.743014.png
1341848217.774807 rgb/1341848217.774807.png 1341848217.774832 depth/1341848217.774832.png
1341848217.806801 rgb/1341848217.806801.png 1341848217.806811 depth/1341848217.806811.png
1341848217.842844 rgb/1341848217.842844.png 1341848217.842858 depth/1341848217.842858.png
1341848217.875051 rgb/1341848217.875051.png 1341848217.875066 depth/1341848217.875066.png
1341848217.906806 rgb/1341848217.906806.png 1341848217.906830 depth/1341848217.906830.png
1341848217.942804 rgb/1341848217.942804.png 1341848217.942817 depth/1341848217.942817.png
1341848217.974980 rgb/1341848217.974980.png 1341848217.974998 depth/1341848217.974998.png
1341848218.010887 rgb/1341848218.010887.png 1341848218.010929 depth/1341848218.010929.png
1341848218.042885 rgb/1341848218.042885.png 1341848218.043101 depth/1341848218.043101.png
1341848218.110994 rgb/1341848218.110994.png 1341848218.111006 depth/1341848218.111006.png
1341848218.142728 rgb/1341848218.142728.png 1341848218.142745 depth/1341848218.142745.png
1341848218.174716 rgb/1341848218.174716.png 1341848218.174748 depth/1341848218.174748.png
1341848218.210732 rgb/1341848218.210732.png 1341848218.210745 depth/1341848218.210745.png
1341848218.242903 rgb/1341848218.242903.png 1341848218.242989 depth/1341848218.242989.png
1341848218.278858 rgb/1341848218.278858.png 1341848218.278888 depth/1341848218.278888.png
1341848218.310953 rgb/1341848218.310953.png 1341848218.310965 depth/1341848218.310965.png
1341848218.342857 rgb/1341848218.342857.png 1341848218.342879 depth/1341848218.342879.png
1341848218.378922 rgb/1341848218.378922.png 1341848218.378936 depth/1341848218.378936.png
1341848218.410819 rgb/1341848218.410819.png 1341848218.410852 depth/1341848218.410852.png
1341848218.446819 rgb/1341848218.446819.png 1341848218.446831 depth/1341848218.446831.png
1341848218.478941 rgb/1341848218.478941.png 1341848218.478954 depth/1341848218.478954.png
1341848218.510807 rgb/1341848218.510807.png 1341848218.510830 depth/1341848218.510830.png
1341848218.546736 rgb/1341848218.546736.png 1341848218.546749 depth/1341848218.546749.png
1341848218.578756 rgb/1341848218.578756.png 1341848218.578775 depth/1341848218.578775.png
1341848218.610904 rgb/1341848218.610904.png 1341848218.611737 depth/1341848218.611737.png
1341848218.646796 rgb/1341848218.646796.png 1341848218.646810 depth/1341848218.646810.png
1341848218.678835 rgb/1341848218.678835.png 1341848218.678847 depth/1341848218.678847.png
1341848218.714933 rgb/1341848218.714933.png 1341848218.714949 depth/1341848218.714949.png
1341848218.746987 rgb/1341848218.746987.png 1341848218.747041 depth/1341848218.747041.png
1341848218.778830 rgb/1341848218.778830.png 1341848218.778840 depth/1341848218.778840.png
1341848218.814916 rgb/1341848218.814916.png 1341848218.814937 depth/1341848218.814937.png
1341848218.846988 rgb/1341848218.846988.png 1341848218.847009 depth/1341848218.847009.png
1341848218.878860 rgb/1341848218.878860.png 1341848218.878875 depth/1341848218.878875.png
1341848218.914863 rgb/1341848218.914863.png 1341848218.914877 depth/1341848218.914877.png
1341848218.946758 rgb/1341848218.946758.png 1341848218.946775 depth/1341848218.946775.png
1341848218.982898 rgb/1341848218.982898.png 1341848218.982916 depth/1341848218.982916.png
1341848219.014846 rgb/1341848219.014846.png 1341848219.015703 depth/1341848219.015703.png
1341848219.046869 rgb/1341848219.046869.png 1341848219.046884 depth/1341848219.046884.png
1341848219.082921 rgb/1341848219.082921.png 1341848219.082934 depth/1341848219.082934.png
1341848219.114860 rgb/1341848219.114860.png 1341848219.114877 depth/1341848219.114877.png
1341848219.146886 rgb/1341848219.146886.png 1341848219.146899 depth/1341848219.146899.png
1341848219.184030 rgb/1341848219.184030.png 1341848219.184081 depth/1341848219.184081.png
1341848219.214947 rgb/1341848219.214947.png 1341848219.214957 depth/1341848219.214957.png
1341848219.250834 rgb/1341848219.250834.png 1341848219.250846 depth/1341848219.250846.png
1341848219.282843 rgb/1341848219.282843.png 1341848219.282858 depth/1341848219.282858.png
1341848219.314875 rgb/1341848219.314875.png 1341848219.314893 depth/1341848219.314893.png
1341848219.350865 rgb/1341848219.350865.png 1341848219.350874 depth/1341848219.350874.png
1341848219.382886 rgb/1341848219.382886.png 1341848219.382910 depth/1341848219.382910.png
1341848219.421931 rgb/1341848219.421931.png 1341848219.421969 depth/1341848219.421969.png
1341848219.482994 rgb/1341848219.482994.png 1341848219.483030 depth/1341848219.483030.png
1341848219.518819 rgb/1341848219.518819.png 1341848219.518850 depth/1341848219.518850.png
1341848219.550802 rgb/1341848219.550802.png 1341848219.550817 depth/1341848219.550817.png
1341848219.582827 rgb/1341848219.582827.png 1341848219.582842 depth/1341848219.582842.png
1341848219.618862 rgb/1341848219.618862.png 1341848219.618876 depth/1341848219.618876.png
1341848219.650878 rgb/1341848219.650878.png 1341848219.651537 depth/1341848219.651537.png
1341848219.686974 rgb/1341848219.686974.png 1341848219.687014 depth/1341848219.687014.png
1341848219.719047 rgb/1341848219.719047.png 1341848219.719064 depth/1341848219.719064.png
1341848219.751015 rgb/1341848219.751015.png 1341848219.751028 depth/1341848219.751028.png
1341848219.786812 rgb/1341848219.786812.png 1341848219.786822 depth/1341848219.786822.png
1341848219.818760 rgb/1341848219.818760.png 1341848219.818774 depth/1341848219.818774.png
1341848219.852057 rgb/1341848219.852057.png 1341848219.852105 depth/1341848219.852105.png
1341848219.886996 rgb/1341848219.886996.png 1341848219.887018 depth/1341848219.887018.png
1341848219.918771 rgb/1341848219.918771.png 1341848219.918787 depth/1341848219.918787.png
1341848219.954840 rgb/1341848219.954840.png 1341848219.954854 depth/1341848219.954854.png
1341848219.986780 rgb/1341848219.986780.png 1341848219.986860 depth/1341848219.986860.png
1341848220.018778 rgb/1341848220.018778.png 1341848220.018801 depth/1341848220.018801.png
1341848220.054710 rgb/1341848220.054710.png 1341848220.054728 depth/1341848220.054728.png
1341848220.086918 rgb/1341848220.086918.png 1341848220.086927 depth/1341848220.086927.png
1341848220.118811 rgb/1341848220.118811.png 1341848220.118821 depth/1341848220.118821.png
1341848220.161870 rgb/1341848220.161870.png 1341848220.161929 depth/1341848220.161929.png
1341848220.222928 rgb/1341848220.222928.png 1341848220.222954 depth/1341848220.222954.png
1341848220.262017 rgb/1341848220.262017.png 1341848220.262028 depth/1341848220.262028.png
1341848220.293849 rgb/1341848220.293849.png 1341848220.293866 depth/1341848220.293866.png
1341848220.329867 rgb/1341848220.329867.png 1341848220.330215 depth/1341848220.330215.png
1341848220.362710 rgb/1341848220.362710.png 1341848220.362727 depth/1341848220.362727.png
1341848220.422848 rgb/1341848220.422848.png 1341848220.422857 depth/1341848220.422857.png
1341848220.455330 rgb/1341848220.455330.png 1341848220.456132 depth/1341848220.456132.png
1341848220.490744 rgb/1341848220.490744.png 1341848220.490770 depth/1341848220.490770.png
1341848220.523087 rgb/1341848220.523087.png 1341848220.523103 depth/1341848220.523103.png
1341848220.554937 rgb/1341848220.554937.png 1341848220.554950 depth/1341848220.554950.png
1341848220.590808 rgb/1341848220.590808.png 1341848220.590836 depth/1341848220.590836.png
1341848220.622879 rgb/1341848220.622879.png 1341848220.622907 depth/1341848220.622907.png
1341848220.661881 rgb/1341848220.661881.png 1341848220.658878 depth/1341848220.658878.png
1341848220.723020 rgb/1341848220.723020.png 1341848220.723072 depth/1341848220.723072.png
1341848220.759586 rgb/1341848220.759586.png 1341848220.759599 depth/1341848220.759599.png
1341848220.790752 rgb/1341848220.790752.png 1341848220.790838 depth/1341848220.790838.png
1341848220.822934 rgb/1341848220.822934.png 1341848220.822947 depth/1341848220.822947.png
1341848220.865954 rgb/1341848220.865954.png 1341848220.865975 depth/1341848220.865975.png
1341848220.926900 rgb/1341848220.926900.png 1341848220.926919 depth/1341848220.926919.png
1341848220.965896 rgb/1341848220.965896.png 1341848220.965929 depth/1341848220.965929.png
1341848221.026861 rgb/1341848221.026861.png 1341848221.026886 depth/1341848221.026886.png
1341848221.059082 rgb/1341848221.059082.png 1341848221.060024 depth/1341848221.060024.png
1341848221.090733 rgb/1341848221.090733.png 1341848221.091213 depth/1341848221.091213.png
1341848221.126819 rgb/1341848221.126819.png 1341848221.126836 depth/1341848221.126836.png
1341848221.158885 rgb/1341848221.158885.png 1341848221.158901 depth/1341848221.158901.png
1341848221.194789 rgb/1341848221.194789.png 1341848221.194828 depth/1341848221.194828.png
1341848221.259120 rgb/1341848221.259120.png 1341848221.259149 depth/1341848221.259149.png
1341848221.295179 rgb/1341848221.295179.png 1341848221.295188 depth/1341848221.295188.png
1341848221.326812 rgb/1341848221.326812.png 1341848221.326832 depth/1341848221.326832.png
1341848221.358991 rgb/1341848221.358991.png 1341848221.359015 depth/1341848221.359015.png
1341848221.394830 rgb/1341848221.394830.png 1341848221.394876 depth/1341848221.394876.png
1341848221.426949 rgb/1341848221.426949.png 1341848221.426961 depth/1341848221.426961.png
1341848221.462885 rgb/1341848221.462885.png 1341848221.462896 depth/1341848221.462896.png
1341848221.494731 rgb/1341848221.494731.png 1341848221.494777 depth/1341848221.494777.png
1341848221.526753 rgb/1341848221.526753.png 1341848221.526781 depth/1341848221.526781.png
1341848221.562863 rgb/1341848221.562863.png 1341848221.562883 depth/1341848221.562883.png
1341848221.594747 rgb/1341848221.594747.png 1341848221.594790 depth/1341848221.594790.png
1341848221.627099 rgb/1341848221.627099.png 1341848221.627119 depth/1341848221.627119.png
1341848221.664087 rgb/1341848221.664087.png 1341848221.664137 depth/1341848221.664137.png
1341848221.694853 rgb/1341848221.694853.png 1341848221.694878 depth/1341848221.694878.png
1341848221.730734 rgb/1341848221.730734.png 1341848221.730746 depth/1341848221.730746.png
1341848221.762851 rgb/1341848221.762851.png 1341848221.762868 depth/1341848221.762868.png
1341848221.794940 rgb/1341848221.794940.png 1341848221.794974 depth/1341848221.794974.png
1341848221.830941 rgb/1341848221.830941.png 1341848221.830952 depth/1341848221.830952.png
1341848221.862905 rgb/1341848221.862905.png 1341848221.862948 depth/1341848221.862948.png
1341848221.898957 rgb/1341848221.898957.png 1341848221.898977 depth/1341848221.898977.png
1341848221.930837 rgb/1341848221.930837.png 1341848221.930847 depth/1341848221.930847.png
1341848221.962755 rgb/1341848221.962755.png 1341848221.962773 depth/1341848221.962773.png
1341848221.998815 rgb/1341848221.998815.png 1341848221.998834 depth/1341848221.998834.png
1341848222.030671 rgb/1341848222.030671.png 1341848222.030689 depth/1341848222.030689.png
1341848222.063018 rgb/1341848222.063018.png 1341848222.063045 depth/1341848222.063045.png
1341848222.098795 rgb/1341848222.098795.png 1341848222.098815 depth/1341848222.098815.png
1341848222.130789 rgb/1341848222.130789.png 1341848222.130805 depth/1341848222.130805.png
1341848222.166857 rgb/1341848222.166857.png 1341848222.166871 depth/1341848222.166871.png
1341848222.198879 rgb/1341848222.198879.png 1341848222.198900 depth/1341848222.198900.png
1341848222.230928 rgb/1341848222.230928.png 1341848222.230958 depth/1341848222.230958.png
1341848222.266814 rgb/1341848222.266814.png 1341848222.266831 depth/1341848222.266831.png
1341848222.298782 rgb/1341848222.298782.png 1341848222.298847 depth/1341848222.298847.png
1341848222.330944 rgb/1341848222.330944.png 1341848222.331093 depth/1341848222.331093.png
1341848222.366859 rgb/1341848222.366859.png 1341848222.366879 depth/1341848222.366879.png
1341848222.398935 rgb/1341848222.398935.png 1341848222.398945 depth/1341848222.398945.png
1341848222.434871 rgb/1341848222.434871.png 1341848222.435083 depth/1341848222.435083.png
1341848222.466810 rgb/1341848222.466810.png 1341848222.466834 depth/1341848222.466834.png
1341848222.498874 rgb/1341848222.498874.png 1341848222.498937 depth/1341848222.498937.png
1341848222.534893 rgb/1341848222.534893.png 1341848222.534920 depth/1341848222.534920.png
1341848222.566846 rgb/1341848222.566846.png 1341848222.566858 depth/1341848222.566858.png
1341848222.598744 rgb/1341848222.598744.png 1341848222.598765 depth/1341848222.598765.png
1341848222.634867 rgb/1341848222.634867.png 1341848222.634887 depth/1341848222.634887.png
1341848222.666780 rgb/1341848222.666780.png 1341848222.666876 depth/1341848222.666876.png
1341848222.702781 rgb/1341848222.702781.png 1341848222.702791 depth/1341848222.702791.png
1341848222.735187 rgb/1341848222.735187.png 1341848222.735221 depth/1341848222.735221.png
1341848222.766831 rgb/1341848222.766831.png 1341848222.766846 depth/1341848222.766846.png
1341848222.802847 rgb/1341848222.802847.png 1341848222.802873 depth/1341848222.802873.png
1341848222.834861 rgb/1341848222.834861.png 1341848222.834873 depth/1341848222.834873.png
1341848222.870737 rgb/1341848222.870737.png 1341848222.870785 depth/1341848222.870785.png
1341848222.903815 rgb/1341848222.903815.png 1341848222.903826 depth/1341848222.903826.png
1341848222.934870 rgb/1341848222.934870.png 1341848222.935045 depth/1341848222.935045.png
1341848222.978011 rgb/1341848222.978011.png 1341848222.978058 depth/1341848222.978058.png
1341848223.034860 rgb/1341848223.034860.png 1341848223.034878 depth/1341848223.034878.png
1341848223.070952 rgb/1341848223.070952.png 1341848223.071077 depth/1341848223.071077.png
1341848223.138826 rgb/1341848223.138826.png 1341848223.138841 depth/1341848223.138841.png
1341848223.171095 rgb/1341848223.171095.png 1341848223.171114 depth/1341848223.171114.png
1341848223.203914 rgb/1341848223.203914.png 1341848223.204592 depth/1341848223.204592.png
1341848223.239221 rgb/1341848223.239221.png 1341848223.240458 depth/1341848223.240458.png
1341848223.270876 rgb/1341848223.270876.png 1341848223.270927 depth/1341848223.270927.png
1341848223.303337 rgb/1341848223.303337.png 1341848223.303378 depth/1341848223.303378.png
1341848223.339092 rgb/1341848223.339092.png 1341848223.339117 depth/1341848223.339117.png
1341848223.371260 rgb/1341848223.371260.png 1341848223.371803 depth/1341848223.371803.png
1341848223.406995 rgb/1341848223.406995.png 1341848223.407798 depth/1341848223.407798.png
1341848223.472775 rgb/1341848223.472775.png 1341848223.473683 depth/1341848223.473683.png
1341848223.511686 rgb/1341848223.511686.png 1341848223.512803 depth/1341848223.512803.png
1341848223.546178 rgb/1341848223.546178.png 1341848223.547352 depth/1341848223.547352.png
1341848223.586864 rgb/1341848223.586864.png 1341848223.588392 depth/1341848223.588392.png
1341848223.614024 rgb/1341848223.614024.png 1341848223.614711 depth/1341848223.614711.png
1341848223.645943 rgb/1341848223.645943.png 1341848223.645964 depth/1341848223.645964.png
1341848223.678400 rgb/1341848223.678400.png 1341848223.678775 depth/1341848223.678775.png
1341848223.713788 rgb/1341848223.713788.png 1341848223.713805 depth/1341848223.713805.png
1341848223.745801 rgb/1341848223.745801.png 1341848223.745837 depth/1341848223.745837.png
1341848223.777997 rgb/1341848223.777997.png 1341848223.778097 depth/1341848223.778097.png
1341848223.814016 rgb/1341848223.814016.png 1341848223.814063 depth/1341848223.814063.png
1341848223.845881 rgb/1341848223.845881.png 1341848223.845891 depth/1341848223.845891.png
1341848223.877830 rgb/1341848223.877830.png 1341848223.878472 depth/1341848223.878472.png
1341848223.913949 rgb/1341848223.913949.png 1341848223.915032 depth/1341848223.915032.png
1341848223.945857 rgb/1341848223.945857.png 1341848223.946332 depth/1341848223.946332.png
1341848224.013871 rgb/1341848224.013871.png 1341848224.013956 depth/1341848224.013956.png
1341848224.074917 rgb/1341848224.074917.png 1341848224.074938 depth/1341848224.074938.png
1341848224.110715 rgb/1341848224.110715.png 1341848224.110723 depth/1341848224.110723.png
1341848224.142829 rgb/1341848224.142829.png 1341848224.142860 depth/1341848224.142860.png
1341848224.210817 rgb/1341848224.210817.png 1341848224.210896 depth/1341848224.210896.png
1341848224.242753 rgb/1341848224.242753.png 1341848224.242771 depth/1341848224.242771.png
1341848224.274851 rgb/1341848224.274851.png 1341848224.274874 depth/1341848224.274874.png
1341848224.310791 rgb/1341848224.310791.png 1341848224.310803 depth/1341848224.310803.png
1341848224.342830 rgb/1341848224.342830.png 1341848224.342843 depth/1341848224.342843.png
1341848224.378755 rgb/1341848224.378755.png 1341848224.378790 depth/1341848224.378790.png
1341848224.410845 rgb/1341848224.410845.png 1341848224.410957 depth/1341848224.410957.png
1341848224.442764 rgb/1341848224.442764.png 1341848224.442800 depth/1341848224.442800.png
1341848224.481872 rgb/1341848224.481872.png 1341848224.481893 depth/1341848224.481893.png
1341848224.542781 rgb/1341848224.542781.png 1341848224.542792 depth/1341848224.542792.png
1341848224.578830 rgb/1341848224.578830.png 1341848224.578849 depth/1341848224.578849.png
1341848224.610809 rgb/1341848224.610809.png 1341848224.611361 depth/1341848224.611361.png
1341848224.646785 rgb/1341848224.646785.png 1341848224.646918 depth/1341848224.646918.png
1341848224.678933 rgb/1341848224.678933.png 1341848224.679001 depth/1341848224.679001.png
1341848224.710830 rgb/1341848224.710830.png 1341848224.710846 depth/1341848224.710846.png
1341848224.746955 rgb/1341848224.746955.png 1341848224.746995 depth/1341848224.746995.png
1341848224.778899 rgb/1341848224.778899.png 1341848224.778912 depth/1341848224.778912.png
1341848224.810919 rgb/1341848224.810919.png 1341848224.811361 depth/1341848224.811361.png
1341848224.846802 rgb/1341848224.846802.png 1341848224.846814 depth/1341848224.846814.png
1341848224.878837 rgb/1341848224.878837.png 1341848224.878852 depth/1341848224.878852.png
1341848224.914841 rgb/1341848224.914841.png 1341848224.914863 depth/1341848224.914863.png
1341848224.946900 rgb/1341848224.946900.png 1341848224.947396 depth/1341848224.947396.png
1341848224.978969 rgb/1341848224.978969.png 1341848224.979819 depth/1341848224.979819.png
1341848225.014875 rgb/1341848225.014875.png 1341848225.014890 depth/1341848225.014890.png
1341848225.046767 rgb/1341848225.046767.png 1341848225.046793 depth/1341848225.046793.png
1341848225.082863 rgb/1341848225.082863.png 1341848225.082884 depth/1341848225.082884.png
1341848225.114817 rgb/1341848225.114817.png 1341848225.115249 depth/1341848225.115249.png
1341848225.146799 rgb/1341848225.146799.png 1341848225.146816 depth/1341848225.146816.png
1341848225.214878 rgb/1341848225.214878.png 1341848225.214897 depth/1341848225.214897.png
1341848225.246987 rgb/1341848225.246987.png 1341848225.247507 depth/1341848225.247507.png
1341848225.282806 rgb/1341848225.282806.png 1341848225.282836 depth/1341848225.282836.png
1341848225.314779 rgb/1341848225.314779.png 1341848225.314800 depth/1341848225.314800.png
1341848225.352016 rgb/1341848225.352016.png 1341848225.352029 depth/1341848225.352029.png
1341848225.382823 rgb/1341848225.382823.png 1341848225.383371 depth/1341848225.383371.png
1341848225.414854 rgb/1341848225.414854.png 1341848225.414867 depth/1341848225.414867.png
1341848225.450882 rgb/1341848225.450882.png 1341848225.450908 depth/1341848225.450908.png
1341848225.482724 rgb/1341848225.482724.png 1341848225.483196 depth/1341848225.483196.png
1341848225.514976 rgb/1341848225.514976.png 1341848225.515006 depth/1341848225.515006.png
1341848225.550834 rgb/1341848225.550834.png 1341848225.550867 depth/1341848225.550867.png
1341848225.582944 rgb/1341848225.582944.png 1341848225.582990 depth/1341848225.582990.png
1341848225.618703 rgb/1341848225.618703.png 1341848225.618715 depth/1341848225.618715.png
1341848225.650850 rgb/1341848225.650850.png 1341848225.650873 depth/1341848225.650873.png
1341848225.682791 rgb/1341848225.682791.png 1341848225.682808 depth/1341848225.682808.png
1341848225.718789 rgb/1341848225.718789.png 1341848225.718809 depth/1341848225.718809.png
1341848225.750879 rgb/1341848225.750879.png 1341848225.750908 depth/1341848225.750908.png
1341848225.782800 rgb/1341848225.782800.png 1341848225.783302 depth/1341848225.783302.png
1341848225.818787 rgb/1341848225.818787.png 1341848225.818862 depth/1341848225.818862.png
1341848225.851468 rgb/1341848225.851468.png 1341848225.851485 depth/1341848225.851485.png
1341848225.886701 rgb/1341848225.886701.png 1341848225.886724 depth/1341848225.886724.png
1341848225.918785 rgb/1341848225.918785.png 1341848225.918821 depth/1341848225.918821.png
1341848225.950916 rgb/1341848225.950916.png 1341848225.951068 depth/1341848225.951068.png
1341848225.986887 rgb/1341848225.986887.png 1341848225.986896 depth/1341848225.986896.png
1341848226.018873 rgb/1341848226.018873.png 1341848226.018888 depth/1341848226.018888.png
1341848226.054881 rgb/1341848226.054881.png 1341848226.055421 depth/1341848226.055421.png
1341848226.086900 rgb/1341848226.086900.png 1341848226.086928 depth/1341848226.086928.png
1341848226.118807 rgb/1341848226.118807.png 1341848226.118836 depth/1341848226.118836.png
1341848226.154771 rgb/1341848226.154771.png 1341848226.154819 depth/1341848226.154819.png
1341848226.186908 rgb/1341848226.186908.png 1341848226.186933 depth/1341848226.186933.png
1341848226.218861 rgb/1341848226.218861.png 1341848226.218878 depth/1341848226.218878.png
1341848226.254754 rgb/1341848226.254754.png 1341848226.254796 depth/1341848226.254796.png
1341848226.286762 rgb/1341848226.286762.png 1341848226.287401 depth/1341848226.287401.png
1341848226.322983 rgb/1341848226.322983.png 1341848226.323009 depth/1341848226.323009.png
1341848226.387060 rgb/1341848226.387060.png 1341848226.387152 depth/1341848226.387152.png
1341848226.422994 rgb/1341848226.422994.png 1341848226.423032 depth/1341848226.423032.png
1341848226.454759 rgb/1341848226.454759.png 1341848226.454794 depth/1341848226.454794.png
1341848226.487092 rgb/1341848226.487092.png 1341848226.487144 depth/1341848226.487144.png
1341848226.522927 rgb/1341848226.522927.png 1341848226.522959 depth/1341848226.522959.png
1341848226.555001 rgb/1341848226.555001.png 1341848226.555019 depth/1341848226.555019.png
1341848226.590812 rgb/1341848226.590812.png 1341848226.590840 depth/1341848226.590840.png
1341848226.622843 rgb/1341848226.622843.png 1341848226.622884 depth/1341848226.622884.png
1341848226.655247 rgb/1341848226.655247.png 1341848226.655265 depth/1341848226.655265.png
1341848226.690909 rgb/1341848226.690909.png 1341848226.690931 depth/1341848226.690931.png
1341848226.722863 rgb/1341848226.722863.png 1341848226.722898 depth/1341848226.722898.png
1341848226.755174 rgb/1341848226.755174.png 1341848226.755192 depth/1341848226.755192.png
1341848226.790731 rgb/1341848226.790731.png 1341848226.790769 depth/1341848226.790769.png
1341848226.822995 rgb/1341848226.822995.png 1341848226.823047 depth/1341848226.823047.png
1341848226.858934 rgb/1341848226.858934.png 1341848226.858968 depth/1341848226.858968.png
1341848226.890905 rgb/1341848226.890905.png 1341848226.890939 depth/1341848226.890939.png
1341848226.922898 rgb/1341848226.922898.png 1341848226.922943 depth/1341848226.922943.png
1341848226.958937 rgb/1341848226.958937.png 1341848226.958963 depth/1341848226.958963.png
1341848226.990756 rgb/1341848226.990756.png 1341848226.990777 depth/1341848226.990777.png
1341848227.022827 rgb/1341848227.022827.png 1341848227.022860 depth/1341848227.022860.png
1341848227.058972 rgb/1341848227.058972.png 1341848227.058987 depth/1341848227.058987.png
1341848227.127129 rgb/1341848227.127129.png 1341848227.127153 depth/1341848227.127153.png
1341848227.158800 rgb/1341848227.158800.png 1341848227.158830 depth/1341848227.158830.png
1341848227.190876 rgb/1341848227.190876.png 1341848227.190893 depth/1341848227.190893.png
1341848227.226757 rgb/1341848227.226757.png 1341848227.226787 depth/1341848227.226787.png
1341848227.258759 rgb/1341848227.258759.png 1341848227.258790 depth/1341848227.258790.png
1341848227.294791 rgb/1341848227.294791.png 1341848227.294805 depth/1341848227.294805.png
1341848227.326950 rgb/1341848227.326950.png 1341848227.327518 depth/1341848227.327518.png
1341848227.359293 rgb/1341848227.359293.png 1341848227.359307 depth/1341848227.359307.png
1341848227.394836 rgb/1341848227.394836.png 1341848227.394874 depth/1341848227.394874.png
1341848227.426778 rgb/1341848227.426778.png 1341848227.426792 depth/1341848227.426792.png
1341848227.458888 rgb/1341848227.458888.png 1341848227.458913 depth/1341848227.458913.png
1341848227.494827 rgb/1341848227.494827.png 1341848227.494840 depth/1341848227.494840.png
1341848227.526971 rgb/1341848227.526971.png 1341848227.527115 depth/1341848227.527115.png
1341848227.562891 rgb/1341848227.562891.png 1341848227.562920 depth/1341848227.562920.png
1341848227.594792 rgb/1341848227.594792.png 1341848227.594807 depth/1341848227.594807.png
1341848227.627005 rgb/1341848227.627005.png 1341848227.627037 depth/1341848227.627037.png
1341848227.662800 rgb/1341848227.662800.png 1341848227.662809 depth/1341848227.662809.png
1341848227.694877 rgb/1341848227.694877.png 1341848227.694903 depth/1341848227.694903.png
1341848227.726776 rgb/1341848227.726776.png 1341848227.726789 depth/1341848227.726789.png
1341848227.762937 rgb/1341848227.762937.png 1341848227.762970 depth/1341848227.762970.png
1341848227.794884 rgb/1341848227.794884.png 1341848227.794898 depth/1341848227.794898.png
1341848227.830913 rgb/1341848227.830913.png 1341848227.830944 depth/1341848227.830944.png
1341848227.869910 rgb/1341848227.869910.png 1341848227.870746 depth/1341848227.870746.png
1341848227.901933 rgb/1341848227.901933.png 1341848227.901944 depth/1341848227.901944.png
1341848227.937883 rgb/1341848227.937883.png 1341848227.937894 depth/1341848227.937894.png
1341848227.970021 rgb/1341848227.970021.png 1341848227.970632 depth/1341848227.970632.png
1341848228.002006 rgb/1341848228.002006.png 1341848228.002033 depth/1341848228.002033.png
1341848228.038624 rgb/1341848228.038624.png 1341848228.038641 depth/1341848228.038641.png
1341848228.069834 rgb/1341848228.069834.png 1341848228.069851 depth/1341848228.069851.png
1341848228.105822 rgb/1341848228.105822.png 1341848228.105835 depth/1341848228.105835.png
1341848228.139043 rgb/1341848228.139043.png 1341848228.139071 depth/1341848228.139071.png
1341848228.170043 rgb/1341848228.170043.png 1341848228.170057 depth/1341848228.170057.png
1341848228.205849 rgb/1341848228.205849.png 1341848228.205870 depth/1341848228.205870.png
1341848228.237803 rgb/1341848228.237803.png 1341848228.238281 depth/1341848228.238281.png
1341848228.273885 rgb/1341848228.273885.png 1341848228.273901 depth/1341848228.273901.png
1341848228.305846 rgb/1341848228.305846.png 1341848228.305877 depth/1341848228.305877.png
1341848228.366949 rgb/1341848228.366949.png 1341848228.366994 depth/1341848228.366994.png
1341848228.398933 rgb/1341848228.398933.png 1341848228.398980 depth/1341848228.398980.png
1341848228.430834 rgb/1341848228.430834.png 1341848228.430922 depth/1341848228.430922.png
1341848228.466866 rgb/1341848228.466866.png 1341848228.466881 depth/1341848228.466881.png
1341848228.498799 rgb/1341848228.498799.png 1341848228.498810 depth/1341848228.498810.png
1341848228.534915 rgb/1341848228.534915.png 1341848228.534954 depth/1341848228.534954.png
1341848228.566817 rgb/1341848228.566817.png 1341848228.566828 depth/1341848228.566828.png
1341848228.598761 rgb/1341848228.598761.png 1341848228.598799 depth/1341848228.598799.png
1341848228.634935 rgb/1341848228.634935.png 1341848228.634979 depth/1341848228.634979.png
1341848228.666861 rgb/1341848228.666861.png 1341848228.666888 depth/1341848228.666888.png
1341848228.698794 rgb/1341848228.698794.png 1341848228.698826 depth/1341848228.698826.png
1341848228.734980 rgb/1341848228.734980.png 1341848228.735035 depth/1341848228.735035.png
1341848228.766852 rgb/1341848228.766852.png 1341848228.766871 depth/1341848228.766871.png
1341848228.802900 rgb/1341848228.802900.png 1341848228.803465 depth/1341848228.803465.png
1341848228.834811 rgb/1341848228.834811.png 1341848228.834823 depth/1341848228.834823.png
1341848228.866924 rgb/1341848228.866924.png 1341848228.866974 depth/1341848228.866974.png
1341848228.902868 rgb/1341848228.902868.png 1341848228.902914 depth/1341848228.902914.png
1341848228.935009 rgb/1341848228.935009.png 1341848228.935019 depth/1341848228.935019.png
1341848228.967100 rgb/1341848228.967100.png 1341848228.967139 depth/1341848228.967139.png
1341848229.002908 rgb/1341848229.002908.png 1341848229.002934 depth/1341848229.002934.png
1341848229.035188 rgb/1341848229.035188.png 1341848229.035232 depth/1341848229.035232.png
1341848229.070927 rgb/1341848229.070927.png 1341848229.070989 depth/1341848229.070989.png
1341848229.102780 rgb/1341848229.102780.png 1341848229.102792 depth/1341848229.102792.png
1341848229.134918 rgb/1341848229.134918.png 1341848229.134945 depth/1341848229.134945.png
1341848229.170872 rgb/1341848229.170872.png 1341848229.170890 depth/1341848229.170890.png
1341848229.202871 rgb/1341848229.202871.png 1341848229.202889 depth/1341848229.202889.png
1341848229.234821 rgb/1341848229.234821.png 1341848229.234867 depth/1341848229.234867.png
1341848229.270899 rgb/1341848229.270899.png 1341848229.270927 depth/1341848229.270927.png
1341848229.303286 rgb/1341848229.303286.png 1341848229.303682 depth/1341848229.303682.png
1341848229.338822 rgb/1341848229.338822.png 1341848229.338847 depth/1341848229.338847.png
1341848229.370807 rgb/1341848229.370807.png 1341848229.370859 depth/1341848229.370859.png
1341848229.402744 rgb/1341848229.402744.png 1341848229.403316 depth/1341848229.403316.png
1341848229.438822 rgb/1341848229.438822.png 1341848229.438835 depth/1341848229.438835.png
1341848229.470830 rgb/1341848229.470830.png 1341848229.470845 depth/1341848229.470845.png
1341848229.506966 rgb/1341848229.506966.png 1341848229.506988 depth/1341848229.506988.png
1341848229.538819 rgb/1341848229.538819.png 1341848229.539687 depth/1341848229.539687.png
1341848229.570811 rgb/1341848229.570811.png 1341848229.570823 depth/1341848229.570823.png
1341848229.606784 rgb/1341848229.606784.png 1341848229.606800 depth/1341848229.606800.png
1341848229.639429 rgb/1341848229.639429.png 1341848229.638861 depth/1341848229.638861.png
1341848229.670857 rgb/1341848229.670857.png 1341848229.670876 depth/1341848229.670876.png
1341848229.706886 rgb/1341848229.706886.png 1341848229.707652 depth/1341848229.707652.png
1341848229.738746 rgb/1341848229.738746.png 1341848229.739345 depth/1341848229.739345.png
1341848229.775128 rgb/1341848229.775128.png 1341848229.775187 depth/1341848229.775187.png
1341848229.806823 rgb/1341848229.806823.png 1341848229.806839 depth/1341848229.806839.png
1341848229.838788 rgb/1341848229.838788.png 1341848229.838800 depth/1341848229.838800.png
1341848229.875201 rgb/1341848229.875201.png 1341848229.875232 depth/1341848229.875232.png
1341848229.906768 rgb/1341848229.906768.png 1341848229.906783 depth/1341848229.906783.png
1341848229.938910 rgb/1341848229.938910.png 1341848229.939538 depth/1341848229.939538.png
1341848229.974790 rgb/1341848229.974790.png 1341848229.974847 depth/1341848229.974847.png
1341848230.006903 rgb/1341848230.006903.png 1341848230.006913 depth/1341848230.006913.png
1341848230.042927 rgb/1341848230.042927.png 1341848230.042938 depth/1341848230.042938.png
1341848230.075210 rgb/1341848230.075210.png 1341848230.075965 depth/1341848230.075965.png
1341848230.109215 rgb/1341848230.109215.png 1341848230.109233 depth/1341848230.109233.png
1341848230.143034 rgb/1341848230.143034.png 1341848230.143630 depth/1341848230.143630.png
1341848230.174902 rgb/1341848230.174902.png 1341848230.175003 depth/1341848230.175003.png
1341848230.206890 rgb/1341848230.206890.png 1341848230.206954 depth/1341848230.206954.png
1341848230.242939 rgb/1341848230.242939.png 1341848230.243550 depth/1341848230.243550.png
1341848230.274754 rgb/1341848230.274754.png 1341848230.274770 depth/1341848230.274770.png
1341848230.312488 rgb/1341848230.312488.png 1341848230.312501 depth/1341848230.312501.png
1341848230.342919 rgb/1341848230.342919.png 1341848230.342938 depth/1341848230.342938.png
1341848230.374822 rgb/1341848230.374822.png 1341848230.374849 depth/1341848230.374849.png
1341848230.410800 rgb/1341848230.410800.png 1341848230.410812 depth/1341848230.410812.png
1341848230.442796 rgb/1341848230.442796.png 1341848230.442830 depth/1341848230.442830.png
1341848230.478737 rgb/1341848230.478737.png 1341848230.478783 depth/1341848230.478783.png
1341848230.510698 rgb/1341848230.510698.png 1341848230.510752 depth/1341848230.510752.png
1341848230.542944 rgb/1341848230.542944.png 1341848230.543529 depth/1341848230.543529.png
1341848230.579078 rgb/1341848230.579078.png 1341848230.579497 depth/1341848230.579497.png
1341848230.610869 rgb/1341848230.610869.png 1341848230.610887 depth/1341848230.610887.png
1341848230.642765 rgb/1341848230.642765.png 1341848230.642794 depth/1341848230.642794.png
1341848230.678844 rgb/1341848230.678844.png 1341848230.678871 depth/1341848230.678871.png
1341848230.710795 rgb/1341848230.710795.png 1341848230.710817 depth/1341848230.710817.png
1341848230.746880 rgb/1341848230.746880.png 1341848230.746900 depth/1341848230.746900.png
1341848230.778756 rgb/1341848230.778756.png 1341848230.779282 depth/1341848230.779282.png
1341848230.810756 rgb/1341848230.810756.png 1341848230.811298 depth/1341848230.811298.png
1341848230.846753 rgb/1341848230.846753.png 1341848230.846766 depth/1341848230.846766.png
1341848230.878844 rgb/1341848230.878844.png 1341848230.878862 depth/1341848230.878862.png
1341848230.910868 rgb/1341848230.910868.png 1341848230.910894 depth/1341848230.910894.png
1341848230.946808 rgb/1341848230.946808.png 1341848230.946821 depth/1341848230.946821.png
1341848230.979221 rgb/1341848230.979221.png 1341848230.979238 depth/1341848230.979238.png
1341848231.014864 rgb/1341848231.014864.png 1341848231.014878 depth/1341848231.014878.png
1341848231.046854 rgb/1341848231.046854.png 1341848231.046869 depth/1341848231.046869.png
1341848231.078864 rgb/1341848231.078864.png 1341848231.079410 depth/1341848231.079410.png
1341848231.114797 rgb/1341848231.114797.png 1341848231.114828 depth/1341848231.114828.png
1341848231.147313 rgb/1341848231.147313.png 1341848231.147362 depth/1341848231.147362.png
1341848231.178788 rgb/1341848231.178788.png 1341848231.178830 depth/1341848231.178830.png
1341848231.214868 rgb/1341848231.214868.png 1341848231.214919 depth/1341848231.214919.png
1341848231.246948 rgb/1341848231.246948.png 1341848231.247005 depth/1341848231.247005.png
1341848231.282931 rgb/1341848231.282931.png 1341848231.282953 depth/1341848231.282953.png
1341848231.314830 rgb/1341848231.314830.png 1341848231.314844 depth/1341848231.314844.png
1341848231.389878 rgb/1341848231.389878.png 1341848231.390351 depth/1341848231.390351.png
1341848231.446973 rgb/1341848231.446973.png 1341848231.446985 depth/1341848231.446985.png
1341848231.483313 rgb/1341848231.483313.png 1341848231.483337 depth/1341848231.483337.png
1341848231.515667 rgb/1341848231.515667.png 1341848231.515730 depth/1341848231.515730.png
1341848231.590000 rgb/1341848231.590000.png 1341848231.590048 depth/1341848231.590048.png
1341848231.650977 rgb/1341848231.650977.png 1341848231.651565 depth/1341848231.651565.png
1341848231.690150 rgb/1341848231.690150.png 1341848231.691753 depth/1341848231.691753.png
1341848231.721953 rgb/1341848231.721953.png 1341848231.721973 depth/1341848231.721973.png
1341848231.754322 rgb/1341848231.754322.png 1341848231.754349 depth/1341848231.754349.png
1341848231.790276 rgb/1341848231.790276.png 1341848231.790854 depth/1341848231.790854.png
1341848231.821771 rgb/1341848231.821771.png 1341848231.822122 depth/1341848231.822122.png
1341848231.853841 rgb/1341848231.853841.png 1341848231.853905 depth/1341848231.853905.png
1341848231.889798 rgb/1341848231.889798.png 1341848231.890283 depth/1341848231.890283.png
1341848231.921716 rgb/1341848231.921716.png 1341848231.921742 depth/1341848231.921742.png
1341848231.957732 rgb/1341848231.957732.png 1341848231.957752 depth/1341848231.957752.png
1341848231.989813 rgb/1341848231.989813.png 1341848231.990176 depth/1341848231.990176.png
1341848232.021938 rgb/1341848232.021938.png 1341848232.021980 depth/1341848232.021980.png
1341848232.057918 rgb/1341848232.057918.png 1341848232.057951 depth/1341848232.057951.png
1341848232.121794 rgb/1341848232.121794.png 1341848232.121836 depth/1341848232.121836.png
1341848232.187105 rgb/1341848232.187105.png 1341848232.187143 depth/1341848232.187143.png
1341848232.220077 rgb/1341848232.220077.png 1341848232.220098 depth/1341848232.220098.png
1341848232.254774 rgb/1341848232.254774.png 1341848232.254790 depth/1341848232.254790.png
1341848232.286727 rgb/1341848232.286727.png 1341848232.287233 depth/1341848232.287233.png
1341848232.319067 rgb/1341848232.319067.png 1341848232.319743 depth/1341848232.319743.png
1341848232.354870 rgb/1341848232.354870.png 1341848232.354899 depth/1341848232.354899.png
1341848232.386828 rgb/1341848232.386828.png 1341848232.386848 depth/1341848232.386848.png
1341848232.419112 rgb/1341848232.419112.png 1341848232.419128 depth/1341848232.419128.png
1341848232.454906 rgb/1341848232.454906.png 1341848232.454929 depth/1341848232.454929.png
1341848232.486697 rgb/1341848232.486697.png 1341848232.486711 depth/1341848232.486711.png
1341848232.522767 rgb/1341848232.522767.png 1341848232.522790 depth/1341848232.522790.png
1341848232.554901 rgb/1341848232.554901.png 1341848232.554929 depth/1341848232.554929.png
1341848232.587076 rgb/1341848232.587076.png 1341848232.587103 depth/1341848232.587103.png
1341848232.622901 rgb/1341848232.622901.png 1341848232.622913 depth/1341848232.622913.png
1341848232.654865 rgb/1341848232.654865.png 1341848232.654957 depth/1341848232.654957.png
1341848232.690756 rgb/1341848232.690756.png 1341848232.690777 depth/1341848232.690777.png
1341848232.722804 rgb/1341848232.722804.png 1341848232.722827 depth/1341848232.722827.png
1341848232.756118 rgb/1341848232.756118.png 1341848232.756135 depth/1341848232.756135.png
1341848232.790798 rgb/1341848232.790798.png 1341848232.790810 depth/1341848232.790810.png
1341848232.822828 rgb/1341848232.822828.png 1341848232.822845 depth/1341848232.822845.png
1341848232.854867 rgb/1341848232.854867.png 1341848232.855566 depth/1341848232.855566.png
1341848232.890721 rgb/1341848232.890721.png 1341848232.890756 depth/1341848232.890756.png
1341848232.922806 rgb/1341848232.922806.png 1341848232.922821 depth/1341848232.922821.png
1341848232.958727 rgb/1341848232.958727.png 1341848232.959331 depth/1341848232.959331.png
1341848232.990722 rgb/1341848232.990722.png 1341848232.990793 depth/1341848232.990793.png
1341848233.022845 rgb/1341848233.022845.png 1341848233.022875 depth/1341848233.022875.png
1341848233.058745 rgb/1341848233.058745.png 1341848233.058764 depth/1341848233.058764.png
1341848233.090867 rgb/1341848233.090867.png 1341848233.090909 depth/1341848233.090909.png
1341848233.122832 rgb/1341848233.122832.png 1341848233.122842 depth/1341848233.122842.png
1341848233.158877 rgb/1341848233.158877.png 1341848233.158926 depth/1341848233.158926.png
1341848233.190814 rgb/1341848233.190814.png 1341848233.190826 depth/1341848233.190826.png
1341848233.258976 rgb/1341848233.258976.png 1341848233.259024 depth/1341848233.259024.png
1341848233.327087 rgb/1341848233.327087.png 1341848233.327322 depth/1341848233.327322.png
1341848233.358974 rgb/1341848233.358974.png 1341848233.358998 depth/1341848233.358998.png
1341848233.390841 rgb/1341848233.390841.png 1341848233.390870 depth/1341848233.390870.png
1341848233.427024 rgb/1341848233.427024.png 1341848233.427047 depth/1341848233.427047.png
1341848233.458983 rgb/1341848233.458983.png 1341848233.458993 depth/1341848233.458993.png
1341848233.494832 rgb/1341848233.494832.png 1341848233.494887 depth/1341848233.494887.png
1341848233.526880 rgb/1341848233.526880.png 1341848233.526958 depth/1341848233.526958.png
1341848233.559019 rgb/1341848233.559019.png 1341848233.559043 depth/1341848233.559043.png
1341848233.594718 rgb/1341848233.594718.png 1341848233.594849 depth/1341848233.594849.png
1341848233.626806 rgb/1341848233.626806.png 1341848233.626820 depth/1341848233.626820.png
1341848233.660022 rgb/1341848233.660022.png 1341848233.660036 depth/1341848233.660036.png
1341848233.695019 rgb/1341848233.695019.png 1341848233.695128 depth/1341848233.695128.png
1341848233.726860 rgb/1341848233.726860.png 1341848233.726871 depth/1341848233.726871.png
1341848233.762841 rgb/1341848233.762841.png 1341848233.762907 depth/1341848233.762907.png
1341848233.794894 rgb/1341848233.794894.png 1341848233.794910 depth/1341848233.794910.png
1341848233.826831 rgb/1341848233.826831.png 1341848233.826864 depth/1341848233.826864.png
1341848233.862840 rgb/1341848233.862840.png 1341848233.862889 depth/1341848233.862889.png
1341848233.894958 rgb/1341848233.894958.png 1341848233.894993 depth/1341848233.894993.png
1341848233.930754 rgb/1341848233.930754.png 1341848233.930767 depth/1341848233.930767.png
1341848233.963141 rgb/1341848233.963141.png 1341848233.963171 depth/1341848233.963171.png
1341848233.994861 rgb/1341848233.994861.png 1341848233.994871 depth/1341848233.994871.png
1341848234.030776 rgb/1341848234.030776.png 1341848234.030792 depth/1341848234.030792.png
1341848234.062877 rgb/1341848234.062877.png 1341848234.062897 depth/1341848234.062897.png
1341848234.094884 rgb/1341848234.094884.png 1341848234.094911 depth/1341848234.094911.png
1341848234.130769 rgb/1341848234.130769.png 1341848234.130792 depth/1341848234.130792.png
1341848234.162744 rgb/1341848234.162744.png 1341848234.162758 depth/1341848234.162758.png
1341848234.198827 rgb/1341848234.198827.png 1341848234.198852 depth/1341848234.198852.png
1341848234.231097 rgb/1341848234.231097.png 1341848234.231142 depth/1341848234.231142.png
1341848234.262830 rgb/1341848234.262830.png 1341848234.262862 depth/1341848234.262862.png
1341848234.298848 rgb/1341848234.298848.png 1341848234.298866 depth/1341848234.298866.png
1341848234.330731 rgb/1341848234.330731.png 1341848234.330742 depth/1341848234.330742.png
1341848234.362763 rgb/1341848234.362763.png 1341848234.362773 depth/1341848234.362773.png
1341848234.398814 rgb/1341848234.398814.png 1341848234.398829 depth/1341848234.398829.png
1341848234.431043 rgb/1341848234.431043.png 1341848234.431068 depth/1341848234.431068.png
1341848234.466825 rgb/1341848234.466825.png 1341848234.466871 depth/1341848234.466871.png
1341848234.498740 rgb/1341848234.498740.png 1341848234.498783 depth/1341848234.498783.png
1341848234.531153 rgb/1341848234.531153.png 1341848234.531175 depth/1341848234.531175.png
1341848234.567209 rgb/1341848234.567209.png 1341848234.567226 depth/1341848234.567226.png
1341848234.598731 rgb/1341848234.598731.png 1341848234.598790 depth/1341848234.598790.png
1341848234.630772 rgb/1341848234.630772.png 1341848234.630780 depth/1341848234.630780.png
1341848234.666885 rgb/1341848234.666885.png 1341848234.666939 depth/1341848234.666939.png
1341848234.698823 rgb/1341848234.698823.png 1341848234.698851 depth/1341848234.698851.png
1341848234.734789 rgb/1341848234.734789.png 1341848234.734840 depth/1341848234.734840.png
1341848234.766915 rgb/1341848234.766915.png 1341848234.766940 depth/1341848234.766940.png
1341848234.798820 rgb/1341848234.798820.png 1341848234.798839 depth/1341848234.798839.png
1341848234.834943 rgb/1341848234.834943.png 1341848234.834969 depth/1341848234.834969.png
1341848234.866779 rgb/1341848234.866779.png 1341848234.866793 depth/1341848234.866793.png
1341848234.902968 rgb/1341848234.902968.png 1341848234.902992 depth/1341848234.902992.png
1341848234.934828 rgb/1341848234.934828.png 1341848234.934858 depth/1341848234.934858.png
1341848234.966822 rgb/1341848234.966822.png 1341848234.966838 depth/1341848234.966838.png
1341848235.002944 rgb/1341848235.002944.png 1341848235.002955 depth/1341848235.002955.png
1341848235.034842 rgb/1341848235.034842.png 1341848235.034879 depth/1341848235.034879.png
1341848235.066770 rgb/1341848235.066770.png 1341848235.066784 depth/1341848235.066784.png
1341848235.103022 rgb/1341848235.103022.png 1341848235.103071 depth/1341848235.103071.png
1341848235.135504 rgb/1341848235.135504.png 1341848235.135515 depth/1341848235.135515.png
1341848235.170895 rgb/1341848235.170895.png 1341848235.170905 depth/1341848235.170905.png
1341848235.202775 rgb/1341848235.202775.png 1341848235.202797 depth/1341848235.202797.png
1341848235.234922 rgb/1341848235.234922.png 1341848235.235107 depth/1341848235.235107.png
1341848235.270829 rgb/1341848235.270829.png 1341848235.270855 depth/1341848235.270855.png
1341848235.302865 rgb/1341848235.302865.png 1341848235.302884 depth/1341848235.302884.png
1341848235.334714 rgb/1341848235.334714.png 1341848235.334746 depth/1341848235.334746.png
1341848235.370909 rgb/1341848235.370909.png 1341848235.370930 depth/1341848235.370930.png
1341848235.402904 rgb/1341848235.402904.png 1341848235.402915 depth/1341848235.402915.png
1341848235.438967 rgb/1341848235.438967.png 1341848235.439450 depth/1341848235.439450.png
1341848235.470840 rgb/1341848235.470840.png 1341848235.470867 depth/1341848235.470867.png
1341848235.503450 rgb/1341848235.503450.png 1341848235.504282 depth/1341848235.504282.png
1341848235.539011 rgb/1341848235.539011.png 1341848235.539026 depth/1341848235.539026.png
1341848235.570935 rgb/1341848235.570935.png 1341848235.570962 depth/1341848235.570962.png
1341848235.602925 rgb/1341848235.602925.png 1341848235.602964 depth/1341848235.602964.png
1341848235.638947 rgb/1341848235.638947.png 1341848235.638971 depth/1341848235.638971.png
1341848235.670761 rgb/1341848235.670761.png 1341848235.670771 depth/1341848235.670771.png
1341848235.706897 rgb/1341848235.706897.png 1341848235.706915 depth/1341848235.706915.png
1341848235.738849 rgb/1341848235.738849.png 1341848235.738871 depth/1341848235.738871.png
1341848235.770944 rgb/1341848235.770944.png 1341848235.770960 depth/1341848235.770960.png
1341848235.806842 rgb/1341848235.806842.png 1341848235.806887 depth/1341848235.806887.png
1341848235.838923 rgb/1341848235.838923.png 1341848235.838969 depth/1341848235.838969.png
1341848235.870837 rgb/1341848235.870837.png 1341848235.870865 depth/1341848235.870865.png
1341848235.906946 rgb/1341848235.906946.png 1341848235.906986 depth/1341848235.906986.png
1341848235.938812 rgb/1341848235.938812.png 1341848235.938912 depth/1341848235.938912.png
1341848235.974957 rgb/1341848235.974957.png 1341848235.974982 depth/1341848235.974982.png
1341848236.006959 rgb/1341848236.006959.png 1341848236.006983 depth/1341848236.006983.png
1341848236.038823 rgb/1341848236.038823.png 1341848236.038837 depth/1341848236.038837.png
1341848236.075046 rgb/1341848236.075046.png 1341848236.075085 depth/1341848236.075085.png
1341848236.106795 rgb/1341848236.106795.png 1341848236.106817 depth/1341848236.106817.png
1341848236.142706 rgb/1341848236.142706.png 1341848236.142798 depth/1341848236.142798.png
1341848236.175027 rgb/1341848236.175027.png 1341848236.175186 depth/1341848236.175186.png
1341848236.206803 rgb/1341848236.206803.png 1341848236.206819 depth/1341848236.206819.png
1341848236.242959 rgb/1341848236.242959.png 1341848236.242976 depth/1341848236.242976.png
1341848236.274935 rgb/1341848236.274935.png 1341848236.274969 depth/1341848236.274969.png
1341848236.306848 rgb/1341848236.306848.png 1341848236.306906 depth/1341848236.306906.png
1341848236.342929 rgb/1341848236.342929.png 1341848236.342940 depth/1341848236.342940.png
1341848236.375304 rgb/1341848236.375304.png 1341848236.375325 depth/1341848236.375325.png
1341848236.410890 rgb/1341848236.410890.png 1341848236.410919 depth/1341848236.410919.png
1341848236.442789 rgb/1341848236.442789.png 1341848236.442816 depth/1341848236.442816.png
1341848236.474899 rgb/1341848236.474899.png 1341848236.475563 depth/1341848236.475563.png
1341848236.510826 rgb/1341848236.510826.png 1341848236.511652 depth/1341848236.511652.png
1341848236.543098 rgb/1341848236.543098.png 1341848236.543792 depth/1341848236.543792.png
1341848236.574910 rgb/1341848236.574910.png 1341848236.575204 depth/1341848236.575204.png
1341848236.610816 rgb/1341848236.610816.png 1341848236.610889 depth/1341848236.610889.png
1341848236.642853 rgb/1341848236.642853.png 1341848236.642867 depth/1341848236.642867.png
1341848236.680574 rgb/1341848236.680574.png 1341848236.680611 depth/1341848236.680611.png
1341848236.710737 rgb/1341848236.710737.png 1341848236.710765 depth/1341848236.710765.png
1341848236.742794 rgb/1341848236.742794.png 1341848236.742825 depth/1341848236.742825.png
1341848236.778867 rgb/1341848236.778867.png 1341848236.778883 depth/1341848236.778883.png
1341848236.811037 rgb/1341848236.811037.png 1341848236.811062 depth/1341848236.811062.png
1341848236.842932 rgb/1341848236.842932.png 1341848236.842953 depth/1341848236.842953.png
1341848236.878946 rgb/1341848236.878946.png 1341848236.878957 depth/1341848236.878957.png
1341848236.910932 rgb/1341848236.910932.png 1341848236.910940 depth/1341848236.910940.png
1341848236.946855 rgb/1341848236.946855.png 1341848236.946907 depth/1341848236.946907.png
1341848236.978889 rgb/1341848236.978889.png 1341848236.978899 depth/1341848236.978899.png
1341848237.010848 rgb/1341848237.010848.png 1341848237.010867 depth/1341848237.010867.png
1341848237.046862 rgb/1341848237.046862.png 1341848237.046894 depth/1341848237.046894.png
1341848237.079221 rgb/1341848237.079221.png 1341848237.079287 depth/1341848237.079287.png
1341848237.114794 rgb/1341848237.114794.png 1341848237.114822 depth/1341848237.114822.png
1341848237.146878 rgb/1341848237.146878.png 1341848237.146932 depth/1341848237.146932.png
1341848237.179932 rgb/1341848237.179932.png 1341848237.179947 depth/1341848237.179947.png
1341848237.214957 rgb/1341848237.214957.png 1341848237.214970 depth/1341848237.214970.png
1341848237.246963 rgb/1341848237.246963.png 1341848237.246976 depth/1341848237.246976.png
1341848237.279050 rgb/1341848237.279050.png 1341848237.279119 depth/1341848237.279119.png
1341848237.315012 rgb/1341848237.315012.png 1341848237.315032 depth/1341848237.315032.png
1341848237.346847 rgb/1341848237.346847.png 1341848237.346858 depth/1341848237.346858.png
1341848237.382927 rgb/1341848237.382927.png 1341848237.382947 depth/1341848237.382947.png
1341848237.415937 rgb/1341848237.415937.png 1341848237.415969 depth/1341848237.415969.png
1341848237.446912 rgb/1341848237.446912.png 1341848237.446929 depth/1341848237.446929.png
1341848237.483028 rgb/1341848237.483028.png 1341848237.483540 depth/1341848237.483540.png
1341848237.514979 rgb/1341848237.514979.png 1341848237.515418 depth/1341848237.515418.png
1341848237.546938 rgb/1341848237.546938.png 1341848237.546969 depth/1341848237.546969.png
1341848237.583029 rgb/1341848237.583029.png 1341848237.583116 depth/1341848237.583116.png
1341848237.614866 rgb/1341848237.614866.png 1341848237.614881 depth/1341848237.614881.png
1341848237.650850 rgb/1341848237.650850.png 1341848237.650888 depth/1341848237.650888.png
1341848237.689945 rgb/1341848237.689945.png 1341848237.689983 depth/1341848237.689983.png
1341848237.722440 rgb/1341848237.722440.png 1341848237.722464 depth/1341848237.722464.png
1341848237.757975 rgb/1341848237.757975.png 1341848237.758014 depth/1341848237.758014.png
1341848237.789885 rgb/1341848237.789885.png 1341848237.789896 depth/1341848237.789896.png
1341848237.821811 rgb/1341848237.821811.png 1341848237.821836 depth/1341848237.821836.png
1341848237.857901 rgb/1341848237.857901.png 1341848237.857924 depth/1341848237.857924.png
1341848237.889829 rgb/1341848237.889829.png 1341848237.889839 depth/1341848237.889839.png
1341848237.925791 rgb/1341848237.925791.png 1341848237.925811 depth/1341848237.925811.png
1341848237.958009 rgb/1341848237.958009.png 1341848237.958035 depth/1341848237.958035.png
1341848237.989808 rgb/1341848237.989808.png 1341848237.989832 depth/1341848237.989832.png
1341848238.025935 rgb/1341848238.025935.png 1341848238.025972 depth/1341848238.025972.png
1341848238.057936 rgb/1341848238.057936.png 1341848238.057957 depth/1341848238.057957.png
1341848238.093880 rgb/1341848238.093880.png 1341848238.093908 depth/1341848238.093908.png
1341848238.125924 rgb/1341848238.125924.png 1341848238.125934 depth/1341848238.125934.png
1341848238.157917 rgb/1341848238.157917.png 1341848238.157996 depth/1341848238.157996.png
1341848238.193917 rgb/1341848238.193917.png 1341848238.194964 depth/1341848238.194964.png
1341848238.225828 rgb/1341848238.225828.png 1341848238.225848 depth/1341848238.225848.png
1341848238.258200 rgb/1341848238.258200.png 1341848238.258224 depth/1341848238.258224.png
1341848238.293884 rgb/1341848238.293884.png 1341848238.293907 depth/1341848238.293907.png
1341848238.325786 rgb/1341848238.325786.png 1341848238.325800 depth/1341848238.325800.png
1341848238.358164 rgb/1341848238.358164.png 1341848238.358207 depth/1341848238.358207.png
1341848238.394109 rgb/1341848238.394109.png 1341848238.394133 depth/1341848238.394133.png
1341848238.426107 rgb/1341848238.426107.png 1341848238.426128 depth/1341848238.426128.png
1341848238.462695 rgb/1341848238.462695.png 1341848238.462725 depth/1341848238.462725.png
1341848238.525940 rgb/1341848238.525940.png 1341848238.525977 depth/1341848238.525977.png
1341848238.587210 rgb/1341848238.587210.png 1341848238.587239 depth/1341848238.587239.png
1341848238.622865 rgb/1341848238.622865.png 1341848238.622885 depth/1341848238.622885.png
1341848238.693993 rgb/1341848238.693993.png 1341848238.694014 depth/1341848238.694014.png
1341848238.757338 rgb/1341848238.757338.png 1341848238.759374 depth/1341848238.759374.png
1341848238.787135 rgb/1341848238.787135.png 1341848238.787154 depth/1341848238.787154.png
1341848238.826197 rgb/1341848238.826197.png 1341848238.827399 depth/1341848238.827399.png
1341848238.855690 rgb/1341848238.855690.png 1341848238.856895 depth/1341848238.856895.png
1341848238.893839 rgb/1341848238.893839.png 1341848238.894974 depth/1341848238.894974.png
1341848238.955108 rgb/1341848238.955108.png 1341848238.955121 depth/1341848238.955121.png
1341848238.990770 rgb/1341848238.990770.png 1341848238.990783 depth/1341848238.990783.png
1341848239.024487 rgb/1341848239.024487.png 1341848239.024613 depth/1341848239.024613.png
1341848239.056707 rgb/1341848239.056707.png 1341848239.056724 depth/1341848239.056724.png
1341848239.122897 rgb/1341848239.122897.png 1341848239.122938 depth/1341848239.122938.png
1341848239.158841 rgb/1341848239.158841.png 1341848239.158854 depth/1341848239.158854.png
1341848239.190772 rgb/1341848239.190772.png 1341848239.190786 depth/1341848239.190786.png
1341848239.222855 rgb/1341848239.222855.png 1341848239.222874 depth/1341848239.222874.png
1341848239.258908 rgb/1341848239.258908.png 1341848239.258953 depth/1341848239.258953.png
1341848239.291204 rgb/1341848239.291204.png 1341848239.291729 depth/1341848239.291729.png
================================================
FILE: Examples/RGB-D/associations/fr3_str_tex_far.txt
================================================
1341839113.657637 rgb/1341839113.657637.png 1341839113.657663 depth/1341839113.657663.png
1341839113.693575 rgb/1341839113.693575.png 1341839113.693593 depth/1341839113.693593.png
1341839113.725606 rgb/1341839113.725606.png 1341839113.725630 depth/1341839113.725630.png
1341839113.793718 rgb/1341839113.793718.png 1341839113.793734 depth/1341839113.793734.png
1341839113.861553 rgb/1341839113.861553.png 1341839113.861564 depth/1341839113.861564.png
1341839113.894400 rgb/1341839113.894400.png 1341839113.894423 depth/1341839113.894423.png
1341839113.925550 rgb/1341839113.925550.png 1341839113.925567 depth/1341839113.925567.png
1341839113.961614 rgb/1341839113.961614.png 1341839113.961650 depth/1341839113.961650.png
1341839113.993616 rgb/1341839113.993616.png 1341839113.993637 depth/1341839113.993637.png
1341839114.025642 rgb/1341839114.025642.png 1341839114.025656 depth/1341839114.025656.png
1341839114.061534 rgb/1341839114.061534.png 1341839114.061547 depth/1341839114.061547.png
1341839114.093617 rgb/1341839114.093617.png 1341839114.093656 depth/1341839114.093656.png
1341839114.129556 rgb/1341839114.129556.png 1341839114.129568 depth/1341839114.129568.png
1341839114.161678 rgb/1341839114.161678.png 1341839114.161687 depth/1341839114.161687.png
1341839114.229673 rgb/1341839114.229673.png 1341839114.229696 depth/1341839114.229696.png
1341839114.261690 rgb/1341839114.261690.png 1341839114.261732 depth/1341839114.261732.png
1341839114.293564 rgb/1341839114.293564.png 1341839114.293581 depth/1341839114.293581.png
1341839114.329671 rgb/1341839114.329671.png 1341839114.329683 depth/1341839114.329683.png
1341839114.361622 rgb/1341839114.361622.png 1341839114.361642 depth/1341839114.361642.png
1341839114.397666 rgb/1341839114.397666.png 1341839114.397683 depth/1341839114.397683.png
1341839114.429583 rgb/1341839114.429583.png 1341839114.429612 depth/1341839114.429612.png
1341839114.461610 rgb/1341839114.461610.png 1341839114.461625 depth/1341839114.461625.png
1341839114.497561 rgb/1341839114.497561.png 1341839114.497571 depth/1341839114.497571.png
1341839114.529492 rgb/1341839114.529492.png 1341839114.529521 depth/1341839114.529521.png
1341839114.565482 rgb/1341839114.565482.png 1341839114.565492 depth/1341839114.565492.png
1341839114.597648 rgb/1341839114.597648.png 1341839114.597672 depth/1341839114.597672.png
1341839114.629596 rgb/1341839114.629596.png 1341839114.629605 depth/1341839114.629605.png
1341839114.665607 rgb/1341839114.665607.png 1341839114.665620 depth/1341839114.665620.png
1341839114.697721 rgb/1341839114.697721.png 1341839114.697742 depth/1341839114.697742.png
1341839114.730054 rgb/1341839114.730054.png 1341839114.730075 depth/1341839114.730075.png
1341839114.765560 rgb/1341839114.765560.png 1341839114.765588 depth/1341839114.765588.png
1341839114.797510 rgb/1341839114.797510.png 1341839114.797529 depth/1341839114.797529.png
1341839114.833570 rgb/1341839114.833570.png 1341839114.833611 depth/1341839114.833611.png
1341839114.865530 rgb/1341839114.865530.png 1341839114.865552 depth/1341839114.865552.png
1341839114.897742 rgb/1341839114.897742.png 1341839114.897759 depth/1341839114.897759.png
1341839114.933721 rgb/1341839114.933721.png 1341839114.933735 depth/1341839114.933735.png
1341839114.965565 rgb/1341839114.965565.png 1341839114.965577 depth/1341839114.965577.png
1341839114.997678 rgb/1341839114.997678.png 1341839114.997693 depth/1341839114.997693.png
1341839115.033675 rgb/1341839115.033675.png 1341839115.033696 depth/1341839115.033696.png
1341839115.065634 rgb/1341839115.065634.png 1341839115.065650 depth/1341839115.065650.png
1341839115.101577 rgb/1341839115.101577.png 1341839115.101593 depth/1341839115.101593.png
1341839115.133455 rgb/1341839115.133455.png 1341839115.133522 depth/1341839115.133522.png
1341839115.165699 rgb/1341839115.165699.png 1341839115.165734 depth/1341839115.165734.png
1341839115.201542 rgb/1341839115.201542.png 1341839115.201580 depth/1341839115.201580.png
1341839115.233600 rgb/1341839115.233600.png 1341839115.233615 depth/1341839115.233615.png
1341839115.265499 rgb/1341839115.265499.png 1341839115.265508 depth/1341839115.265508.png
1341839115.301699 rgb/1341839115.301699.png 1341839115.301713 depth/1341839115.301713.png
1341839115.333616 rgb/1341839115.333616.png 1341839115.333623 depth/1341839115.333623.png
1341839115.369483 rgb/1341839115.369483.png 1341839115.369499 depth/1341839115.369499.png
1341839115.401613 rgb/1341839115.401613.png 1341839115.401633 depth/1341839115.401633.png
1341839115.469819 rgb/1341839115.469819.png 1341839115.469842 depth/1341839115.469842.png
1341839115.533671 rgb/1341839115.533671.png 1341839115.533679 depth/1341839115.533679.png
1341839115.569633 rgb/1341839115.569633.png 1341839115.569790 depth/1341839115.569790.png
1341839115.601623 rgb/1341839115.601623.png 1341839115.601639 depth/1341839115.601639.png
1341839115.637954 rgb/1341839115.637954.png 1341839115.637973 depth/1341839115.637973.png
1341839115.669467 rgb/1341839115.669467.png 1341839115.669503 depth/1341839115.669503.png
1341839115.701635 rgb/1341839115.701635.png 1341839115.701664 depth/1341839115.701664.png
1341839115.737552 rgb/1341839115.737552.png 1341839115.737567 depth/1341839115.737567.png
1341839115.769579 rgb/1341839115.769579.png 1341839115.769589 depth/1341839115.769589.png
1341839115.805533 rgb/1341839115.805533.png 1341839115.805545 depth/1341839115.805545.png
1341839115.837641 rgb/1341839115.837641.png 1341839115.837655 depth/1341839115.837655.png
1341839115.869594 rgb/1341839115.869594.png 1341839115.869610 depth/1341839115.869610.png
1341839115.905464 rgb/1341839115.905464.png 1341839115.905477 depth/1341839115.905477.png
1341839115.937926 rgb/1341839115.937926.png 1341839115.937940 depth/1341839115.937940.png
1341839115.976772 rgb/1341839115.976772.png 1341839115.976803 depth/1341839115.976803.png
1341839116.037844 rgb/1341839116.037844.png 1341839116.037863 depth/1341839116.037863.png
1341839116.073614 rgb/1341839116.073614.png 1341839116.073625 depth/1341839116.073625.png
1341839116.105551 rgb/1341839116.105551.png 1341839116.105562 depth/1341839116.105562.png
1341839116.137629 rgb/1341839116.137629.png 1341839116.137643 depth/1341839116.137643.png
1341839116.173741 rgb/1341839116.173741.png 1341839116.173765 depth/1341839116.173765.png
1341839116.205705 rgb/1341839116.205705.png 1341839116.205729 depth/1341839116.205729.png
1341839116.237744 rgb/1341839116.237744.png 1341839116.237753 depth/1341839116.237753.png
1341839116.273644 rgb/1341839116.273644.png 1341839116.273652 depth/1341839116.273652.png
1341839116.305590 rgb/1341839116.305590.png 1341839116.305631 depth/1341839116.305631.png
1341839116.341693 rgb/1341839116.341693.png 1341839116.341705 depth/1341839116.341705.png
1341839116.374159 rgb/1341839116.374159.png 1341839116.374180 depth/1341839116.374180.png
1341839116.405626 rgb/1341839116.405626.png 1341839116.405654 depth/1341839116.405654.png
1341839116.441448 rgb/1341839116.441448.png 1341839116.441468 depth/1341839116.441468.png
1341839116.473792 rgb/1341839116.473792.png 1341839116.473807 depth/1341839116.473807.png
1341839116.505559 rgb/1341839116.505559.png 1341839116.505628 depth/1341839116.505628.png
1341839116.541530 rgb/1341839116.541530.png 1341839116.541549 depth/1341839116.541549.png
1341839116.573449 rgb/1341839116.573449.png 1341839116.573467 depth/1341839116.573467.png
1341839116.609629 rgb/1341839116.609629.png 1341839116.609652 depth/1341839116.609652.png
1341839116.642092 rgb/1341839116.642092.png 1341839116.642102 depth/1341839116.642102.png
1341839116.673494 rgb/1341839116.673494.png 1341839116.673509 depth/1341839116.673509.png
1341839116.709491 rgb/1341839116.709491.png 1341839116.709501 depth/1341839116.709501.png
1341839116.741798 rgb/1341839116.741798.png 1341839116.741832 depth/1341839116.741832.png
1341839116.777780 rgb/1341839116.777780.png 1341839116.777815 depth/1341839116.777815.png
1341839116.809493 rgb/1341839116.809493.png 1341839116.809672 depth/1341839116.809672.png
1341839116.841577 rgb/1341839116.841577.png 1341839116.841609 depth/1341839116.841609.png
1341839116.877541 rgb/1341839116.877541.png 1341839116.877569 depth/1341839116.877569.png
1341839116.909607 rgb/1341839116.909607.png 1341839116.909614 depth/1341839116.909614.png
1341839116.941574 rgb/1341839116.941574.png 1341839116.941962 depth/1341839116.941962.png
1341839116.977669 rgb/1341839116.977669.png 1341839116.977741 depth/1341839116.977741.png
1341839117.009692 rgb/1341839117.009692.png 1341839117.010335 depth/1341839117.010335.png
1341839117.045446 rgb/1341839117.045446.png 1341839117.045473 depth/1341839117.045473.png
1341839117.077581 rgb/1341839117.077581.png 1341839117.077610 depth/1341839117.077610.png
1341839117.109633 rgb/1341839117.109633.png 1341839117.109645 depth/1341839117.109645.png
1341839117.145451 rgb/1341839117.145451.png 1341839117.145488 depth/1341839117.145488.png
1341839117.177591 rgb/1341839117.177591.png 1341839117.177601 depth/1341839117.177601.png
1341839117.209585 rgb/1341839117.209585.png 1341839117.209615 depth/1341839117.209615.png
1341839117.245753 rgb/1341839117.245753.png 1341839117.245784 depth/1341839117.245784.png
1341839117.278976 rgb/1341839117.278976.png 1341839117.279032 depth/1341839117.279032.png
1341839117.313580 rgb/1341839117.313580.png 1341839117.313591 depth/1341839117.313591.png
1341839117.345623 rgb/1341839117.345623.png 1341839117.345648 depth/1341839117.345648.png
1341839117.377641 rgb/1341839117.377641.png 1341839117.378160 depth/1341839117.378160.png
1341839117.413568 rgb/1341839117.413568.png 1341839117.413600 depth/1341839117.413600.png
1341839117.445717 rgb/1341839117.445717.png 1341839117.445739 depth/1341839117.445739.png
1341839117.477601 rgb/1341839117.477601.png 1341839117.478035 depth/1341839117.478035.png
1341839117.513635 rgb/1341839117.513635.png 1341839117.513644 depth/1341839117.513644.png
1341839117.545603 rgb/1341839117.545603.png 1341839117.545628 depth/1341839117.545628.png
1341839117.581707 rgb/1341839117.581707.png 1341839117.581832 depth/1341839117.581832.png
1341839117.613653 rgb/1341839117.613653.png 1341839117.613672 depth/1341839117.613672.png
1341839117.645887 rgb/1341839117.645887.png 1341839117.646046 depth/1341839117.646046.png
1341839117.681569 rgb/1341839117.681569.png 1341839117.681589 depth/1341839117.681589.png
1341839117.713639 rgb/1341839117.713639.png 1341839117.713657 depth/1341839117.713657.png
1341839117.745712 rgb/1341839117.745712.png 1341839117.746254 depth/1341839117.746254.png
1341839117.781725 rgb/1341839117.781725.png 1341839117.781733 depth/1341839117.781733.png
1341839117.813499 rgb/1341839117.813499.png 1341839117.813509 depth/1341839117.813509.png
1341839117.849617 rgb/1341839117.849617.png 1341839117.849630 depth/1341839117.849630.png
1341839117.881610 rgb/1341839117.881610.png 1341839117.881622 depth/1341839117.881622.png
1341839117.913581 rgb/1341839117.913581.png 1341839117.913608 depth/1341839117.913608.png
1341839117.949521 rgb/1341839117.949521.png 1341839117.949533 depth/1341839117.949533.png
1341839117.981586 rgb/1341839117.981586.png 1341839117.981600 depth/1341839117.981600.png
1341839118.017504 rgb/1341839118.017504.png 1341839118.017560 depth/1341839118.017560.png
1341839118.049478 rgb/1341839118.049478.png 1341839118.049521 depth/1341839118.049521.png
1341839118.081566 rgb/1341839118.081566.png 1341839118.081579 depth/1341839118.081579.png
1341839118.117532 rgb/1341839118.117532.png 1341839118.117557 depth/1341839118.117557.png
1341839118.149476 rgb/1341839118.149476.png 1341839118.149510 depth/1341839118.149510.png
1341839118.182394 rgb/1341839118.182394.png 1341839118.182891 depth/1341839118.182891.png
1341839118.217697 rgb/1341839118.217697.png 1341839118.217718 depth/1341839118.217718.png
1341839118.249595 rgb/1341839118.249595.png 1341839118.249607 depth/1341839118.249607.png
1341839118.285581 rgb/1341839118.285581.png 1341839118.285635 depth/1341839118.285635.png
1341839118.317574 rgb/1341839118.317574.png 1341839118.318164 depth/1341839118.318164.png
1341839118.349685 rgb/1341839118.349685.png 1341839118.349699 depth/1341839118.349699.png
1341839118.385618 rgb/1341839118.385618.png 1341839118.385634 depth/1341839118.385634.png
1341839118.417611 rgb/1341839118.417611.png 1341839118.417702 depth/1341839118.417702.png
1341839118.449697 rgb/1341839118.449697.png 1341839118.449705 depth/1341839118.449705.png
1341839118.485493 rgb/1341839118.485493.png 1341839118.485527 depth/1341839118.485527.png
1341839118.517623 rgb/1341839118.517623.png 1341839118.517638 depth/1341839118.517638.png
1341839118.554050 rgb/1341839118.554050.png 1341839118.554701 depth/1341839118.554701.png
1341839118.585668 rgb/1341839118.585668.png 1341839118.585694 depth/1341839118.585694.png
1341839118.617700 rgb/1341839118.617700.png 1341839118.618254 depth/1341839118.618254.png
1341839118.653714 rgb/1341839118.653714.png 1341839118.653800 depth/1341839118.653800.png
1341839118.717504 rgb/1341839118.717504.png 1341839118.717532 depth/1341839118.717532.png
1341839118.753742 rgb/1341839118.753742.png 1341839118.753754 depth/1341839118.753754.png
1341839118.785566 rgb/1341839118.785566.png 1341839118.785590 depth/1341839118.785590.png
1341839118.821695 rgb/1341839118.821695.png 1341839118.821704 depth/1341839118.821704.png
1341839118.853833 rgb/1341839118.853833.png 1341839118.853844 depth/1341839118.853844.png
1341839118.921740 rgb/1341839118.921740.png 1341839118.921789 depth/1341839118.921789.png
1341839118.953665 rgb/1341839118.953665.png 1341839118.953675 depth/1341839118.953675.png
1341839118.989622 rgb/1341839118.989622.png 1341839118.989643 depth/1341839118.989643.png
1341839119.021687 rgb/1341839119.021687.png 1341839119.021704 depth/1341839119.021704.png
1341839119.054550 rgb/1341839119.054550.png 1341839119.054708 depth/1341839119.054708.png
1341839119.089581 rgb/1341839119.089581.png 1341839119.089606 depth/1341839119.089606.png
1341839119.121679 rgb/1341839119.121679.png 1341839119.121693 depth/1341839119.121693.png
1341839119.153810 rgb/1341839119.153810.png 1341839119.153827 depth/1341839119.153827.png
1341839119.190466 rgb/1341839119.190466.png 1341839119.190502 depth/1341839119.190502.png
1341839119.221601 rgb/1341839119.221601.png 1341839119.222133 depth/1341839119.222133.png
1341839119.257728 rgb/1341839119.257728.png 1341839119.257789 depth/1341839119.257789.png
1341839119.289455 rgb/1341839119.289455.png 1341839119.289469 depth/1341839119.289469.png
1341839119.321569 rgb/1341839119.321569.png 1341839119.321579 depth/1341839119.321579.png
1341839119.357502 rgb/1341839119.357502.png 1341839119.357517 depth/1341839119.357517.png
1341839119.389594 rgb/1341839119.389594.png 1341839119.389633 depth/1341839119.389633.png
1341839119.421517 rgb/1341839119.421517.png 1341839119.421544 depth/1341839119.421544.png
1341839119.457571 rgb/1341839119.457571.png 1341839119.457590 depth/1341839119.457590.png
1341839119.489537 rgb/1341839119.489537.png 1341839119.489563 depth/1341839119.489563.png
1341839119.525734 rgb/1341839119.525734.png 1341839119.525800 depth/1341839119.525800.png
1341839119.557461 rgb/1341839119.557461.png 1341839119.557474 depth/1341839119.557474.png
1341839119.589618 rgb/1341839119.589618.png 1341839119.589631 depth/1341839119.589631.png
1341839119.625979 rgb/1341839119.625979.png 1341839119.626045 depth/1341839119.626045.png
1341839119.657625 rgb/1341839119.657625.png 1341839119.657647 depth/1341839119.657647.png
1341839119.689899 rgb/1341839119.689899.png 1341839119.689921 depth/1341839119.689921.png
1341839119.725735 rgb/1341839119.725735.png 1341839119.725747 depth/1341839119.725747.png
1341839119.757807 rgb/1341839119.757807.png 1341839119.757831 depth/1341839119.757831.png
1341839119.793744 rgb/1341839119.793744.png 1341839119.793779 depth/1341839119.793779.png
1341839119.825500 rgb/1341839119.825500.png 1341839119.825516 depth/1341839119.825516.png
1341839119.857554 rgb/1341839119.857554.png 1341839119.858150 depth/1341839119.858150.png
1341839119.893748 rgb/1341839119.893748.png 1341839119.893763 depth/1341839119.893763.png
1341839119.925601 rgb/1341839119.925601.png 1341839119.926093 depth/1341839119.926093.png
1341839119.957678 rgb/1341839119.957678.png 1341839119.958406 depth/1341839119.958406.png
1341839119.993679 rgb/1341839119.993679.png 1341839119.993686 depth/1341839119.993686.png
1341839120.025666 rgb/1341839120.025666.png 1341839120.025686 depth/1341839120.025686.png
1341839120.061576 rgb/1341839120.061576.png 1341839120.062082 depth/1341839120.062082.png
1341839120.093515 rgb/1341839120.093515.png 1341839120.093523 depth/1341839120.093523.png
1341839120.125657 rgb/1341839120.125657.png 1341839120.125669 depth/1341839120.125669.png
1341839120.161703 rgb/1341839120.161703.png 1341839120.162177 depth/1341839120.162177.png
1341839120.193590 rgb/1341839120.193590.png 1341839120.193629 depth/1341839120.193629.png
1341839120.229713 rgb/1341839120.229713.png 1341839120.229734 depth/1341839120.229734.png
1341839120.261506 rgb/1341839120.261506.png 1341839120.261531 depth/1341839120.261531.png
1341839120.293457 rgb/1341839120.293457.png 1341839120.293477 depth/1341839120.293477.png
1341839120.329588 rgb/1341839120.329588.png 1341839120.329608 depth/1341839120.329608.png
1341839120.361629 rgb/1341839120.361629.png 1341839120.361652 depth/1341839120.361652.png
1341839120.393790 rgb/1341839120.393790.png 1341839120.393811 depth/1341839120.393811.png
1341839120.429559 rgb/1341839120.429559.png 1341839120.429594 depth/1341839120.429594.png
1341839120.461550 rgb/1341839120.461550.png 1341839120.461562 depth/1341839120.461562.png
1341839120.497665 rgb/1341839120.497665.png 1341839120.498550 depth/1341839120.498550.png
1341839120.561630 rgb/1341839120.561630.png 1341839120.561638 depth/1341839120.561638.png
1341839120.597681 rgb/1341839120.597681.png 1341839120.598284 depth/1341839120.598284.png
1341839120.629503 rgb/1341839120.629503.png 1341839120.629533 depth/1341839120.629533.png
1341839120.661993 rgb/1341839120.661993.png 1341839120.662049 depth/1341839120.662049.png
1341839120.697745 rgb/1341839120.697745.png 1341839120.697843 depth/1341839120.697843.png
1341839120.729566 rgb/1341839120.729566.png 1341839120.729590 depth/1341839120.729590.png
1341839120.765550 rgb/1341839120.765550.png 1341839120.765569 depth/1341839120.765569.png
1341839120.797761 rgb/1341839120.797761.png 1341839120.797781 depth/1341839120.797781.png
1341839120.829557 rgb/1341839120.829557.png 1341839120.829571 depth/1341839120.829571.png
1341839120.865525 rgb/1341839120.865525.png 1341839120.865538 depth/1341839120.865538.png
1341839120.897669 rgb/1341839120.897669.png 1341839120.897682 depth/1341839120.897682.png
1341839120.929785 rgb/1341839120.929785.png 1341839120.929849 depth/1341839120.929849.png
1341839120.965555 rgb/1341839120.965555.png 1341839120.965578 depth/1341839120.965578.png
1341839120.997581 rgb/1341839120.997581.png 1341839120.998014 depth/1341839120.998014.png
1341839121.033744 rgb/1341839121.033744.png 1341839121.033752 depth/1341839121.033752.png
1341839121.065604 rgb/1341839121.065604.png 1341839121.065660 depth/1341839121.065660.png
1341839121.097656 rgb/1341839121.097656.png 1341839121.097688 depth/1341839121.097688.png
1341839121.133691 rgb/1341839121.133691.png 1341839121.133718 depth/1341839121.133718.png
1341839121.165530 rgb/1341839121.165530.png 1341839121.165544 depth/1341839121.165544.png
1341839121.201575 rgb/1341839121.201575.png 1341839121.201584 depth/1341839121.201584.png
1341839121.233546 rgb/1341839121.233546.png 1341839121.233558 depth/1341839121.233558.png
1341839121.265498 rgb/1341839121.265498.png 1341839121.265521 depth/1341839121.265521.png
1341839121.301532 rgb/1341839121.301532.png 1341839121.301543 depth/1341839121.301543.png
1341839121.333608 rgb/1341839121.333608.png 1341839121.333879 depth/1341839121.333879.png
1341839121.365570 rgb/1341839121.365570.png 1341839121.365588 depth/1341839121.365588.png
1341839121.401586 rgb/1341839121.401586.png 1341839121.401600 depth/1341839121.401600.png
1341839121.433568 rgb/1341839121.433568.png 1341839121.434084 depth/1341839121.434084.png
1341839121.470470 rgb/1341839121.470470.png 1341839121.470493 depth/1341839121.470493.png
1341839121.501558 rgb/1341839121.501558.png 1341839121.501577 depth/1341839121.501577.png
1341839121.533669 rgb/1341839121.533669.png 1341839121.533709 depth/1341839121.533709.png
1341839121.569551 rgb/1341839121.569551.png 1341839121.569571 depth/1341839121.569571.png
1341839121.601594 rgb/1341839121.601594.png 1341839121.601606 depth/1341839121.601606.png
1341839121.633518 rgb/1341839121.633518.png 1341839121.633582 depth/1341839121.633582.png
1341839121.676759 rgb/1341839121.676759.png 1341839121.676801 depth/1341839121.676801.png
1341839121.737794 rgb/1341839121.737794.png 1341839121.737834 depth/1341839121.737834.png
1341839121.769806 rgb/1341839121.769806.png 1341839121.770350 depth/1341839121.770350.png
1341839121.801610 rgb/1341839121.801610.png 1341839121.801621 depth/1341839121.801621.png
1341839121.837558 rgb/1341839121.837558.png 1341839121.837588 depth/1341839121.837588.png
1341839121.869640 rgb/1341839121.869640.png 1341839121.869902 depth/1341839121.869902.png
1341839121.901603 rgb/1341839121.901603.png 1341839121.901614 depth/1341839121.901614.png
1341839121.937642 rgb/1341839121.937642.png 1341839121.937650 depth/1341839121.937650.png
1341839121.969593 rgb/1341839121.969593.png 1341839121.969901 depth/1341839121.969901.png
1341839122.005447 rgb/1341839122.005447.png 1341839122.005490 depth/1341839122.005490.png
1341839122.037577 rgb/1341839122.037577.png 1341839122.037600 depth/1341839122.037600.png
1341839122.069508 rgb/1341839122.069508.png 1341839122.069517 depth/1341839122.069517.png
1341839122.105677 rgb/1341839122.105677.png 1341839122.105701 depth/1341839122.105701.png
1341839122.137560 rgb/1341839122.137560.png 1341839122.137572 depth/1341839122.137572.png
1341839122.169506 rgb/1341839122.169506.png 1341839122.169531 depth/1341839122.169531.png
1341839122.205699 rgb/1341839122.205699.png 1341839122.206115 depth/1341839122.206115.png
1341839122.237714 rgb/1341839122.237714.png 1341839122.237733 depth/1341839122.237733.png
1341839122.273692 rgb/1341839122.273692.png 1341839122.273705 depth/1341839122.273705.png
1341839122.305536 rgb/1341839122.305536.png 1341839122.305570 depth/1341839122.305570.png
1341839122.337539 rgb/1341839122.337539.png 1341839122.337640 depth/1341839122.337640.png
1341839122.373595 rgb/1341839122.373595.png 1341839122.373679 depth/1341839122.373679.png
1341839122.405534 rgb/1341839122.405534.png 1341839122.405550 depth/1341839122.405550.png
1341839122.441566 rgb/1341839122.441566.png 1341839122.441583 depth/1341839122.441583.png
1341839122.476666 rgb/1341839122.476666.png 1341839122.476743 depth/1341839122.476743.png
1341839122.541642 rgb/1341839122.541642.png 1341839122.541663 depth/1341839122.541663.png
1341839122.605781 rgb/1341839122.605781.png 1341839122.605887 depth/1341839122.605887.png
1341839122.641573 rgb/1341839122.641573.png 1341839122.641592 depth/1341839122.641592.png
1341839122.673585 rgb/1341839122.673585.png 1341839122.674153 depth/1341839122.674153.png
1341839122.709612 rgb/1341839122.709612.png 1341839122.709650 depth/1341839122.709650.png
1341839122.744481 rgb/1341839122.744481.png 1341839122.744517 depth/1341839122.744517.png
1341839122.809572 rgb/1341839122.809572.png 1341839122.809587 depth/1341839122.809587.png
1341839122.841637 rgb/1341839122.841637.png 1341839122.842331 depth/1341839122.842331.png
1341839122.873612 rgb/1341839122.873612.png 1341839122.873662 depth/1341839122.873662.png
1341839122.909624 rgb/1341839122.909624.png 1341839122.909687 depth/1341839122.909687.png
1341839122.941543 rgb/1341839122.941543.png 1341839122.941589 depth/1341839122.941589.png
1341839122.977575 rgb/1341839122.977575.png 1341839122.977601 depth/1341839122.977601.png
1341839123.009572 rgb/1341839123.009572.png 1341839123.009587 depth/1341839123.009587.png
1341839123.041702 rgb/1341839123.041702.png 1341839123.041727 depth/1341839123.041727.png
1341839123.077583 rgb/1341839123.077583.png 1341839123.077612 depth/1341839123.077612.png
1341839123.109751 rgb/1341839123.109751.png 1341839123.109774 depth/1341839123.109774.png
1341839123.141926 rgb/1341839123.141926.png 1341839123.142716 depth/1341839123.142716.png
1341839123.177759 rgb/1341839123.177759.png 1341839123.178137 depth/1341839123.178137.png
1341839123.209570 rgb/1341839123.209570.png 1341839123.209585 depth/1341839123.209585.png
1341839123.245725 rgb/1341839123.245725.png 1341839123.245749 depth/1341839123.245749.png
1341839123.277647 rgb/1341839123.277647.png 1341839123.277667 depth/1341839123.277667.png
1341839123.309620 rgb/1341839123.309620.png 1341839123.309634 depth/1341839123.309634.png
1341839123.345630 rgb/1341839123.345630.png 1341839123.345650 depth/1341839123.345650.png
1341839123.378204 rgb/1341839123.378204.png 1341839123.378227 depth/1341839123.378227.png
1341839123.413605 rgb/1341839123.413605.png 1341839123.413625 depth/1341839123.413625.png
1341839123.445605 rgb/1341839123.445605.png 1341839123.445618 depth/1341839123.445618.png
1341839123.477524 rgb/1341839123.477524.png 1341839123.477537 depth/1341839123.477537.png
1341839123.513569 rgb/1341839123.513569.png 1341839123.513609 depth/1341839123.513609.png
1341839123.545681 rgb/1341839123.545681.png 1341839123.545736 depth/1341839123.545736.png
1341839123.577643 rgb/1341839123.577643.png 1341839123.577657 depth/1341839123.577657.png
1341839123.613598 rgb/1341839123.613598.png 1341839123.613606 depth/1341839123.613606.png
1341839123.645669 rgb/1341839123.645669.png 1341839123.645678 depth/1341839123.645678.png
1341839123.681751 rgb/1341839123.681751.png 1341839123.681788 depth/1341839123.681788.png
1341839123.713662 rgb/1341839123.713662.png 1341839123.713688 depth/1341839123.713688.png
1341839123.745702 rgb/1341839123.745702.png 1341839123.745715 depth/1341839123.745715.png
1341839123.781632 rgb/1341839123.781632.png 1341839123.781644 depth/1341839123.781644.png
1341839123.813710 rgb/1341839123.813710.png 1341839123.813763 depth/1341839123.813763.png
1341839123.845656 rgb/1341839123.845656.png 1341839123.845672 depth/1341839123.845672.png
1341839123.881576 rgb/1341839123.881576.png 1341839123.881630 depth/1341839123.881630.png
1341839123.913827 rgb/1341839123.913827.png 1341839123.913850 depth/1341839123.913850.png
1341839123.949667 rgb/1341839123.949667.png 1341839123.949682 depth/1341839123.949682.png
1341839123.981668 rgb/1341839123.981668.png 1341839123.981687 depth/1341839123.981687.png
1341839124.013726 rgb/1341839124.013726.png 1341839124.013749 depth/1341839124.013749.png
1341839124.049634 rgb/1341839124.049634.png 1341839124.049715 depth/1341839124.049715.png
1341839124.081682 rgb/1341839124.081682.png 1341839124.081734 depth/1341839124.081734.png
1341839124.113596 rgb/1341839124.113596.png 1341839124.113604 depth/1341839124.113604.png
1341839124.149548 rgb/1341839124.149548.png 1341839124.149574 depth/1341839124.149574.png
1341839124.181547 rgb/1341839124.181547.png 1341839124.181563 depth/1341839124.181563.png
1341839124.217783 rgb/1341839124.217783.png 1341839124.217814 depth/1341839124.217814.png
1341839124.256572 rgb/1341839124.256572.png 1341839124.249849 depth/1341839124.249849.png
1341839124.317542 rgb/1341839124.317542.png 1341839124.317575 depth/1341839124.317575.png
1341839124.349622 rgb/1341839124.349622.png 1341839124.349673 depth/1341839124.349673.png
1341839124.417782 rgb/1341839124.417782.png 1341839124.417797 depth/1341839124.417797.png
1341839124.449587 rgb/1341839124.449587.png 1341839124.449597 depth/1341839124.449597.png
1341839124.485711 rgb/1341839124.485711.png 1341839124.485734 depth/1341839124.485734.png
1341839124.549607 rgb/1341839124.549607.png 1341839124.550027 depth/1341839124.550027.png
1341839124.585623 rgb/1341839124.585623.png 1341839124.585651 depth/1341839124.585651.png
1341839124.617614 rgb/1341839124.617614.png 1341839124.617783 depth/1341839124.617783.png
1341839124.653561 rgb/1341839124.653561.png 1341839124.653573 depth/1341839124.653573.png
1341839124.685611 rgb/1341839124.685611.png 1341839124.685623 depth/1341839124.685623.png
1341839124.717580 rgb/1341839124.717580.png 1341839124.717702 depth/1341839124.717702.png
1341839124.753621 rgb/1341839124.753621.png 1341839124.753651 depth/1341839124.753651.png
1341839124.785678 rgb/1341839124.785678.png 1341839124.785724 depth/1341839124.785724.png
1341839124.817558 rgb/1341839124.817558.png 1341839124.817580 depth/1341839124.817580.png
1341839124.885712 rgb/1341839124.885712.png 1341839124.885730 depth/1341839124.885730.png
1341839124.921721 rgb/1341839124.921721.png 1341839124.921744 depth/1341839124.921744.png
1341839124.953580 rgb/1341839124.953580.png 1341839124.953591 depth/1341839124.953591.png
1341839124.985862 rgb/1341839124.985862.png 1341839124.985870 depth/1341839124.985870.png
1341839125.021660 rgb/1341839125.021660.png 1341839125.021865 depth/1341839125.021865.png
1341839125.053606 rgb/1341839125.053606.png 1341839125.053630 depth/1341839125.053630.png
1341839125.086082 rgb/1341839125.086082.png 1341839125.086101 depth/1341839125.086101.png
1341839125.121616 rgb/1341839125.121616.png 1341839125.121631 depth/1341839125.121631.png
1341839125.153540 rgb/1341839125.153540.png 1341839125.153551 depth/1341839125.153551.png
1341839125.189545 rgb/1341839125.189545.png 1341839125.189564 depth/1341839125.189564.png
1341839125.221519 rgb/1341839125.221519.png 1341839125.221564 depth/1341839125.221564.png
1341839125.253620 rgb/1341839125.253620.png 1341839125.253665 depth/1341839125.253665.png
1341839125.289646 rgb/1341839125.289646.png 1341839125.289666 depth/1341839125.289666.png
1341839125.321651 rgb/1341839125.321651.png 1341839125.321674 depth/1341839125.321674.png
1341839125.353612 rgb/1341839125.353612.png 1341839125.353627 depth/1341839125.353627.png
1341839125.389732 rgb/1341839125.389732.png 1341839125.389760 depth/1341839125.389760.png
1341839125.421568 rgb/1341839125.421568.png 1341839125.421575 depth/1341839125.421575.png
1341839125.457605 rgb/1341839125.457605.png 1341839125.457644 depth/1341839125.457644.png
1341839125.489491 rgb/1341839125.489491.png 1341839125.489501 depth/1341839125.489501.png
1341839125.521521 rgb/1341839125.521521.png 1341839125.521569 depth/1341839125.521569.png
1341839125.557578 rgb/1341839125.557578.png 1341839125.557591 depth/1341839125.557591.png
1341839125.596685 rgb/1341839125.596685.png 1341839125.596729 depth/1341839125.596729.png
1341839125.657655 rgb/1341839125.657655.png 1341839125.657797 depth/1341839125.657797.png
1341839125.689599 rgb/1341839125.689599.png 1341839125.690072 depth/1341839125.690072.png
1341839125.725674 rgb/1341839125.725674.png 1341839125.725693 depth/1341839125.725693.png
1341839125.757650 rgb/1341839125.757650.png 1341839125.757671 depth/1341839125.757671.png
1341839125.789697 rgb/1341839125.789697.png 1341839125.789738 depth/1341839125.789738.png
1341839125.825554 rgb/1341839125.825554.png 1341839125.825570 depth/1341839125.825570.png
1341839125.857601 rgb/1341839125.857601.png 1341839125.857614 depth/1341839125.857614.png
1341839125.893542 rgb/1341839125.893542.png 1341839125.893553 depth/1341839125.893553.png
1341839125.925748 rgb/1341839125.925748.png 1341839125.925756 depth/1341839125.925756.png
1341839125.957565 rgb/1341839125.957565.png 1341839125.957592 depth/1341839125.957592.png
1341839125.993528 rgb/1341839125.993528.png 1341839125.993600 depth/1341839125.993600.png
1341839126.025584 rgb/1341839126.025584.png 1341839126.025601 depth/1341839126.025601.png
1341839126.057677 rgb/1341839126.057677.png 1341839126.057694 depth/1341839126.057694.png
1341839126.093586 rgb/1341839126.093586.png 1341839126.093647 depth/1341839126.093647.png
1341839126.125584 rgb/1341839126.125584.png 1341839126.125605 depth/1341839126.125605.png
1341839126.161675 rgb/1341839126.161675.png 1341839126.161697 depth/1341839126.161697.png
1341839126.193566 rgb/1341839126.193566.png 1341839126.193590 depth/1341839126.193590.png
1341839126.225494 rgb/1341839126.225494.png 1341839126.225527 depth/1341839126.225527.png
1341839126.262252 rgb/1341839126.262252.png 1341839126.262271 depth/1341839126.262271.png
1341839126.293564 rgb/1341839126.293564.png 1341839126.293586 depth/1341839126.293586.png
1341839126.325643 rgb/1341839126.325643.png 1341839126.325656 depth/1341839126.325656.png
1341839126.361562 rgb/1341839126.361562.png 1341839126.361590 depth/1341839126.361590.png
1341839126.393475 rgb/1341839126.393475.png 1341839126.393517 depth/1341839126.393517.png
1341839126.429534 rgb/1341839126.429534.png 1341839126.429545 depth/1341839126.429545.png
1341839126.461585 rgb/1341839126.461585.png 1341839126.461608 depth/1341839126.461608.png
1341839126.493573 rgb/1341839126.493573.png 1341839126.494019 depth/1341839126.494019.png
1341839126.529589 rgb/1341839126.529589.png 1341839126.529605 depth/1341839126.529605.png
1341839126.561488 rgb/1341839126.561488.png 1341839126.561522 depth/1341839126.561522.png
1341839126.593549 rgb/1341839126.593549.png 1341839126.593587 depth/1341839126.593587.png
1341839126.629751 rgb/1341839126.629751.png 1341839126.629764 depth/1341839126.629764.png
1341839126.661503 rgb/1341839126.661503.png 1341839126.661581 depth/1341839126.661581.png
1341839126.697561 rgb/1341839126.697561.png 1341839126.697574 depth/1341839126.697574.png
1341839126.729517 rgb/1341839126.729517.png 1341839126.729533 depth/1341839126.729533.png
1341839126.761554 rgb/1341839126.761554.png 1341839126.761749 depth/1341839126.761749.png
1341839126.797734 rgb/1341839126.797734.png 1341839126.797746 depth/1341839126.797746.png
1341839126.829608 rgb/1341839126.829608.png 1341839126.829633 depth/1341839126.829633.png
1341839126.865650 rgb/1341839126.865650.png 1341839126.865668 depth/1341839126.865668.png
1341839126.897640 rgb/1341839126.897640.png 1341839126.897660 depth/1341839126.897660.png
1341839126.929680 rgb/1341839126.929680.png 1341839126.929767 depth/1341839126.929767.png
1341839126.965564 rgb/1341839126.965564.png 1341839126.965600 depth/1341839126.965600.png
1341839126.997665 rgb/1341839126.997665.png 1341839126.997674 depth/1341839126.997674.png
1341839127.029597 rgb/1341839127.029597.png 1341839127.029615 depth/1341839127.029615.png
1341839127.065594 rgb/1341839127.065594.png 1341839127.065615 depth/1341839127.065615.png
1341839127.097689 rgb/1341839127.097689.png 1341839127.097715 depth/1341839127.097715.png
1341839127.133571 rgb/1341839127.133571.png 1341839127.133618 depth/1341839127.133618.png
1341839127.165684 rgb/1341839127.165684.png 1341839127.165733 depth/1341839127.165733.png
1341839127.197636 rgb/1341839127.197636.png 1341839127.197663 depth/1341839127.197663.png
1341839127.233596 rgb/1341839127.233596.png 1341839127.233621 depth/1341839127.233621.png
1341839127.265755 rgb/1341839127.265755.png 1341839127.265775 depth/1341839127.265775.png
1341839127.297673 rgb/1341839127.297673.png 1341839127.297695 depth/1341839127.297695.png
1341839127.333679 rgb/1341839127.333679.png 1341839127.333702 depth/1341839127.333702.png
1341839127.372174 rgb/1341839127.372174.png 1341839127.372929 depth/1341839127.372929.png
1341839127.401871 rgb/1341839127.401871.png 1341839127.403014 depth/1341839127.403014.png
1341839127.434153 rgb/1341839127.434153.png 1341839127.435026 depth/1341839127.435026.png
1341839127.465725 rgb/1341839127.465725.png 1341839127.465735 depth/1341839127.465735.png
1341839127.502087 rgb/1341839127.502087.png 1341839127.502101 depth/1341839127.502101.png
1341839127.533614 rgb/1341839127.533614.png 1341839127.533637 depth/1341839127.533637.png
1341839127.565666 rgb/1341839127.565666.png 1341839127.565871 depth/1341839127.565871.png
1341839127.601497 rgb/1341839127.601497.png 1341839127.601511 depth/1341839127.601511.png
1341839127.633641 rgb/1341839127.633641.png 1341839127.633657 depth/1341839127.633657.png
1341839127.669721 rgb/1341839127.669721.png 1341839127.669739 depth/1341839127.669739.png
1341839127.701590 rgb/1341839127.701590.png 1341839127.701606 depth/1341839127.701606.png
1341839127.733628 rgb/1341839127.733628.png 1341839127.733638 depth/1341839127.733638.png
1341839127.769756 rgb/1341839127.769756.png 1341839127.769782 depth/1341839127.769782.png
1341839127.801629 rgb/1341839127.801629.png 1341839127.802181 depth/1341839127.802181.png
1341839127.837525 rgb/1341839127.837525.png 1341839127.837534 depth/1341839127.837534.png
1341839127.869904 rgb/1341839127.869904.png 1341839127.870065 depth/1341839127.870065.png
1341839127.901787 rgb/1341839127.901787.png 1341839127.901846 depth/1341839127.901846.png
1341839127.937458 rgb/1341839127.937458.png 1341839127.937489 depth/1341839127.937489.png
1341839127.970000 rgb/1341839127.970000.png 1341839127.970627 depth/1341839127.970627.png
1341839128.001556 rgb/1341839128.001556.png 1341839128.001579 depth/1341839128.001579.png
1341839128.037646 rgb/1341839128.037646.png 1341839128.037671 depth/1341839128.037671.png
1341839128.069528 rgb/1341839128.069528.png 1341839128.069541 depth/1341839128.069541.png
1341839128.105485 rgb/1341839128.105485.png 1341839128.105501 depth/1341839128.105501.png
1341839128.137556 rgb/1341839128.137556.png 1341839128.138295 depth/1341839128.138295.png
1341839128.169766 rgb/1341839128.169766.png 1341839128.169799 depth/1341839128.169799.png
1341839128.205769 rgb/1341839128.205769.png 1341839128.205784 depth/1341839128.205784.png
1341839128.237693 rgb/1341839128.237693.png 1341839128.237713 depth/1341839128.237713.png
1341839128.269778 rgb/1341839128.269778.png 1341839128.269799 depth/1341839128.269799.png
1341839128.305489 rgb/1341839128.305489.png 1341839128.305502 depth/1341839128.305502.png
1341839128.337488 rgb/1341839128.337488.png 1341839128.337510 depth/1341839128.337510.png
1341839128.373648 rgb/1341839128.373648.png 1341839128.373669 depth/1341839128.373669.png
1341839128.405628 rgb/1341839128.405628.png 1341839128.405639 depth/1341839128.405639.png
1341839128.438499 rgb/1341839128.438499.png 1341839128.438573 depth/1341839128.438573.png
1341839128.473696 rgb/1341839128.473696.png 1341839128.473733 depth/1341839128.473733.png
1341839128.505546 rgb/1341839128.505546.png 1341839128.505612 depth/1341839128.505612.png
1341839128.537583 rgb/1341839128.537583.png 1341839128.537658 depth/1341839128.537658.png
1341839128.573515 rgb/1341839128.573515.png 1341839128.573552 depth/1341839128.573552.png
1341839128.605707 rgb/1341839128.605707.png 1341839128.605727 depth/1341839128.605727.png
1341839128.641615 rgb/1341839128.641615.png 1341839128.641632 depth/1341839128.641632.png
1341839128.674297 rgb/1341839128.674297.png 1341839128.674920 depth/1341839128.674920.png
1341839128.705724 rgb/1341839128.705724.png 1341839128.705740 depth/1341839128.705740.png
1341839128.741577 rgb/1341839128.741577.png 1341839128.742207 depth/1341839128.742207.png
1341839128.773449 rgb/1341839128.773449.png 1341839128.773460 depth/1341839128.773460.png
1341839128.805626 rgb/1341839128.805626.png 1341839128.805641 depth/1341839128.805641.png
1341839128.841524 rgb/1341839128.841524.png 1341839128.841539 depth/1341839128.841539.png
1341839128.873613 rgb/1341839128.873613.png 1341839128.873656 depth/1341839128.873656.png
1341839128.909718 rgb/1341839128.909718.png 1341839128.909735 depth/1341839128.909735.png
1341839128.941487 rgb/1341839128.941487.png 1341839128.941495 depth/1341839128.941495.png
1341839128.973556 rgb/1341839128.973556.png 1341839128.973591 depth/1341839128.973591.png
1341839129.009679 rgb/1341839129.009679.png 1341839129.009689 depth/1341839129.009689.png
1341839129.041584 rgb/1341839129.041584.png 1341839129.041607 depth/1341839129.041607.png
1341839129.077533 rgb/1341839129.077533.png 1341839129.077558 depth/1341839129.077558.png
1341839129.109520 rgb/1341839129.109520.png 1341839129.109556 depth/1341839129.109556.png
1341839129.141619 rgb/1341839129.141619.png 1341839129.141627 depth/1341839129.141627.png
1341839129.177574 rgb/1341839129.177574.png 1341839129.177582 depth/1341839129.177582.png
1341839129.209655 rgb/1341839129.209655.png 1341839129.209674 depth/1341839129.209674.png
1341839129.241510 rgb/1341839129.241510.png 1341839129.241519 depth/1341839129.241519.png
1341839129.277541 rgb/1341839129.277541.png 1341839129.277553 depth/1341839129.277553.png
1341839129.309548 rgb/1341839129.309548.png 1341839129.309565 depth/1341839129.309565.png
1341839129.345615 rgb/1341839129.345615.png 1341839129.345627 depth/1341839129.345627.png
1341839129.377515 rgb/1341839129.377515.png 1341839129.377530 depth/1341839129.377530.png
1341839129.409635 rgb/1341839129.409635.png 1341839129.409649 depth/1341839129.409649.png
1341839129.445518 rgb/1341839129.445518.png 1341839129.445529 depth/1341839129.445529.png
1341839129.477523 rgb/1341839129.477523.png 1341839129.477534 depth/1341839129.477534.png
1341839129.509566 rgb/1341839129.509566.png 1341839129.509582 depth/1341839129.509582.png
1341839129.545536 rgb/1341839129.545536.png 1341839129.545555 depth/1341839129.545555.png
1341839129.577541 rgb/1341839129.577541.png 1341839129.577559 depth/1341839129.577559.png
1341839129.613707 rgb/1341839129.613707.png 1341839129.613729 depth/1341839129.613729.png
1341839129.645497 rgb/1341839129.645497.png 1341839129.645519 depth/1341839129.645519.png
1341839129.677529 rgb/1341839129.677529.png 1341839129.677690 depth/1341839129.677690.png
1341839129.713807 rgb/1341839129.713807.png 1341839129.713820 depth/1341839129.713820.png
1341839129.745656 rgb/1341839129.745656.png 1341839129.745670 depth/1341839129.745670.png
1341839129.777553 rgb/1341839129.777553.png 1341839129.777564 depth/1341839129.777564.png
1341839129.813668 rgb/1341839129.813668.png 1341839129.813737 depth/1341839129.813737.png
1341839129.845557 rgb/1341839129.845557.png 1341839129.845703 depth/1341839129.845703.png
1341839129.881595 rgb/1341839129.881595.png 1341839129.881622 depth/1341839129.881622.png
1341839129.913656 rgb/1341839129.913656.png 1341839129.913673 depth/1341839129.913673.png
1341839129.945668 rgb/1341839129.945668.png 1341839129.945681 depth/1341839129.945681.png
1341839129.981581 rgb/1341839129.981581.png 1341839129.981601 depth/1341839129.981601.png
1341839130.013837 rgb/1341839130.013837.png 1341839130.013849 depth/1341839130.013849.png
1341839130.049672 rgb/1341839130.049672.png 1341839130.049686 depth/1341839130.049686.png
1341839130.081470 rgb/1341839130.081470.png 1341839130.081559 depth/1341839130.081559.png
1341839130.113580 rgb/1341839130.113580.png 1341839130.113635 depth/1341839130.113635.png
1341839130.149498 rgb/1341839130.149498.png 1341839130.149505 depth/1341839130.149505.png
1341839130.181614 rgb/1341839130.181614.png 1341839130.181637 depth/1341839130.181637.png
1341839130.213597 rgb/1341839130.213597.png 1341839130.213610 depth/1341839130.213610.png
1341839130.249495 rgb/1341839130.249495.png 1341839130.249536 depth/1341839130.249536.png
1341839130.281707 rgb/1341839130.281707.png 1341839130.281723 depth/1341839130.281723.png
1341839130.317659 rgb/1341839130.317659.png 1341839130.317710 depth/1341839130.317710.png
1341839130.349604 rgb/1341839130.349604.png 1341839130.349627 depth/1341839130.349627.png
1341839130.382034 rgb/1341839130.382034.png 1341839130.382042 depth/1341839130.382042.png
1341839130.417728 rgb/1341839130.417728.png 1341839130.417741 depth/1341839130.417741.png
1341839130.481948 rgb/1341839130.481948.png 1341839130.481966 depth/1341839130.481966.png
1341839130.517772 rgb/1341839130.517772.png 1341839130.517798 depth/1341839130.517798.png
1341839130.549519 rgb/1341839130.549519.png 1341839130.549528 depth/1341839130.549528.png
1341839130.585696 rgb/1341839130.585696.png 1341839130.585714 depth/1341839130.585714.png
1341839130.617684 rgb/1341839130.617684.png 1341839130.617718 depth/1341839130.617718.png
1341839130.649566 rgb/1341839130.649566.png 1341839130.649594 depth/1341839130.649594.png
1341839130.685466 rgb/1341839130.685466.png 1341839130.685514 depth/1341839130.685514.png
1341839130.717517 rgb/1341839130.717517.png 1341839130.717526 depth/1341839130.717526.png
1341839130.749572 rgb/1341839130.749572.png 1341839130.749585 depth/1341839130.749585.png
1341839130.785686 rgb/1341839130.785686.png 1341839130.785731 depth/1341839130.785731.png
1341839130.817796 rgb/1341839130.817796.png 1341839130.817808 depth/1341839130.817808.png
1341839130.854788 rgb/1341839130.854788.png 1341839130.854839 depth/1341839130.854839.png
1341839130.885541 rgb/1341839130.885541.png 1341839130.885562 depth/1341839130.885562.png
1341839130.917632 rgb/1341839130.917632.png 1341839130.917661 depth/1341839130.917661.png
1341839130.953712 rgb/1341839130.953712.png 1341839130.953729 depth/1341839130.953729.png
1341839130.985630 rgb/1341839130.985630.png 1341839130.985652 depth/1341839130.985652.png
1341839131.017560 rgb/1341839131.017560.png 1341839131.017580 depth/1341839131.017580.png
1341839131.053526 rgb/1341839131.053526.png 1341839131.053539 depth/1341839131.053539.png
1341839131.085681 rgb/1341839131.085681.png 1341839131.085696 depth/1341839131.085696.png
1341839131.121737 rgb/1341839131.121737.png 1341839131.121752 depth/1341839131.121752.png
1341839131.153629 rgb/1341839131.153629.png 1341839131.153653 depth/1341839131.153653.png
1341839131.185722 rgb/1341839131.185722.png 1341839131.185748 depth/1341839131.185748.png
1341839131.221649 rgb/1341839131.221649.png 1341839131.221694 depth/1341839131.221694.png
1341839131.253615 rgb/1341839131.253615.png 1341839131.253631 depth/1341839131.253631.png
1341839131.289544 rgb/1341839131.289544.png 1341839131.289561 depth/1341839131.289561.png
1341839131.321742 rgb/1341839131.321742.png 1341839131.322248 depth/1341839131.322248.png
1341839131.353559 rgb/1341839131.353559.png 1341839131.353573 depth/1341839131.353573.png
1341839131.389563 rgb/1341839131.389563.png 1341839131.389669 depth/1341839131.389669.png
1341839131.422027 rgb/1341839131.422027.png 1341839131.422054 depth/1341839131.422054.png
1341839131.453618 rgb/1341839131.453618.png 1341839131.453637 depth/1341839131.453637.png
1341839131.489531 rgb/1341839131.489531.png 1341839131.490178 depth/1341839131.490178.png
1341839131.521613 rgb/1341839131.521613.png 1341839131.521627 depth/1341839131.521627.png
1341839131.557577 rgb/1341839131.557577.png 1341839131.557635 depth/1341839131.557635.png
1341839131.589573 rgb/1341839131.589573.png 1341839131.589595 depth/1341839131.589595.png
1341839131.621822 rgb/1341839131.621822.png 1341839131.621841 depth/1341839131.621841.png
1341839131.657680 rgb/1341839131.657680.png 1341839131.657733 depth/1341839131.657733.png
1341839131.689554 rgb/1341839131.689554.png 1341839131.689567 depth/1341839131.689567.png
1341839131.721592 rgb/1341839131.721592.png 1341839131.721604 depth/1341839131.721604.png
1341839131.757613 rgb/1341839131.757613.png 1341839131.757626 depth/1341839131.757626.png
1341839131.789523 rgb/1341839131.789523.png 1341839131.789543 depth/1341839131.789543.png
1341839131.825565 rgb/1341839131.825565.png 1341839131.825591 depth/1341839131.825591.png
1341839131.857572 rgb/1341839131.857572.png 1341839131.857658 depth/1341839131.857658.png
1341839131.889513 rgb/1341839131.889513.png 1341839131.889551 depth/1341839131.889551.png
1341839131.925750 rgb/1341839131.925750.png 1341839131.925782 depth/1341839131.925782.png
1341839131.964633 rgb/1341839131.964633.png 1341839131.964702 depth/1341839131.964702.png
1341839132.025660 rgb/1341839132.025660.png 1341839132.025687 depth/1341839132.025687.png
1341839132.057881 rgb/1341839132.057881.png 1341839132.057902 depth/1341839132.057902.png
1341839132.093669 rgb/1341839132.093669.png 1341839132.093693 depth/1341839132.093693.png
1341839132.125565 rgb/1341839132.125565.png 1341839132.125577 depth/1341839132.125577.png
1341839132.157636 rgb/1341839132.157636.png 1341839132.157647 depth/1341839132.157647.png
1341839132.193673 rgb/1341839132.193673.png 1341839132.193681 depth/1341839132.193681.png
1341839132.225804 rgb/1341839132.225804.png 1341839132.225817 depth/1341839132.225817.png
1341839132.261812 rgb/1341839132.261812.png 1341839132.262262 depth/1341839132.262262.png
1341839132.293590 rgb/1341839132.293590.png 1341839132.293623 depth/1341839132.293623.png
1341839132.325554 rgb/1341839132.325554.png 1341839132.325679 depth/1341839132.325679.png
1341839132.361528 rgb/1341839132.361528.png 1341839132.361535 depth/1341839132.361535.png
1341839132.393650 rgb/1341839132.393650.png 1341839132.393667 depth/1341839132.393667.png
1341839132.425622 rgb/1341839132.425622.png 1341839132.425634 depth/1341839132.425634.png
1341839132.461663 rgb/1341839132.461663.png 1341839132.461671 depth/1341839132.461671.png
1341839132.493798 rgb/1341839132.493798.png 1341839132.493835 depth/1341839132.493835.png
1341839132.529690 rgb/1341839132.529690.png 1341839132.529728 depth/1341839132.529728.png
1341839132.561519 rgb/1341839132.561519.png 1341839132.561537 depth/1341839132.561537.png
1341839132.593700 rgb/1341839132.593700.png 1341839132.593905 depth/1341839132.593905.png
1341839132.629507 rgb/1341839132.629507.png 1341839132.629758 depth/1341839132.629758.png
1341839132.661576 rgb/1341839132.661576.png 1341839132.661595 depth/1341839132.661595.png
1341839132.693571 rgb/1341839132.693571.png 1341839132.693604 depth/1341839132.693604.png
1341839132.729515 rgb/1341839132.729515.png 1341839132.729524 depth/1341839132.729524.png
1341839132.761625 rgb/1341839132.761625.png 1341839132.761643 depth/1341839132.761643.png
1341839132.797547 rgb/1341839132.797547.png 1341839132.797561 depth/1341839132.797561.png
1341839132.829637 rgb/1341839132.829637.png 1341839132.829675 depth/1341839132.829675.png
1341839132.861592 rgb/1341839132.861592.png 1341839132.861615 depth/1341839132.861615.png
1341839132.897486 rgb/1341839132.897486.png 1341839132.897498 depth/1341839132.897498.png
1341839132.929713 rgb/1341839132.929713.png 1341839132.929749 depth/1341839132.929749.png
1341839132.961705 rgb/1341839132.961705.png 1341839132.961719 depth/1341839132.961719.png
1341839132.997927 rgb/1341839132.997927.png 1341839132.997942 depth/1341839132.997942.png
1341839133.029816 rgb/1341839133.029816.png 1341839133.029824 depth/1341839133.029824.png
1341839133.065602 rgb/1341839133.065602.png 1341839133.065673 depth/1341839133.065673.png
1341839133.097540 rgb/1341839133.097540.png 1341839133.097620 depth/1341839133.097620.png
1341839133.129508 rgb/1341839133.129508.png 1341839133.129523 depth/1341839133.129523.png
1341839133.165630 rgb/1341839133.165630.png 1341839133.165642 depth/1341839133.165642.png
1341839133.197576 rgb/1341839133.197576.png 1341839133.197583 depth/1341839133.197583.png
1341839133.229574 rgb/1341839133.229574.png 1341839133.229594 depth/1341839133.229594.png
1341839133.265549 rgb/1341839133.265549.png 1341839133.265591 depth/1341839133.265591.png
1341839133.297600 rgb/1341839133.297600.png 1341839133.297609 depth/1341839133.297609.png
1341839133.333601 rgb/1341839133.333601.png 1341839133.333647 depth/1341839133.333647.png
1341839133.365789 rgb/1341839133.365789.png 1341839133.365812 depth/1341839133.365812.png
1341839133.397692 rgb/1341839133.397692.png 1341839133.397732 depth/1341839133.397732.png
1341839133.433673 rgb/1341839133.433673.png 1341839133.433740 depth/1341839133.433740.png
1341839133.465589 rgb/1341839133.465589.png 1341839133.465597 depth/1341839133.465597.png
1341839133.501571 rgb/1341839133.501571.png 1341839133.501580 depth/1341839133.501580.png
1341839133.533533 rgb/1341839133.533533.png 1341839133.533554 depth/1341839133.533554.png
1341839133.565553 rgb/1341839133.565553.png 1341839133.565575 depth/1341839133.565575.png
1341839133.633642 rgb/1341839133.633642.png 1341839133.633671 depth/1341839133.633671.png
1341839133.672597 rgb/1341839133.672597.png 1341839133.672610 depth/1341839133.672610.png
1341839133.708834 rgb/1341839133.708834.png 1341839133.708869 depth/1341839133.708869.png
1341839133.740662 rgb/1341839133.740662.png 1341839133.740680 depth/1341839133.740680.png
1341839133.776632 rgb/1341839133.776632.png 1341839133.776655 depth/1341839133.776655.png
1341839133.808566 rgb/1341839133.808566.png 1341839133.808578 depth/1341839133.808578.png
1341839133.842375 rgb/1341839133.842375.png 1341839133.842385 depth/1341839133.842385.png
1341839133.876620 rgb/1341839133.876620.png 1341839133.876627 depth/1341839133.876627.png
1341839133.908528 rgb/1341839133.908528.png 1341839133.908540 depth/1341839133.908540.png
1341839133.940713 rgb/1341839133.940713.png 1341839133.940728 depth/1341839133.940728.png
1341839133.976740 rgb/1341839133.976740.png 1341839133.976761 depth/1341839133.976761.png
1341839134.008547 rgb/1341839134.008547.png 1341839134.008597 depth/1341839134.008597.png
1341839134.040599 rgb/1341839134.040599.png 1341839134.040610 depth/1341839134.040610.png
1341839134.076583 rgb/1341839134.076583.png 1341839134.076596 depth/1341839134.076596.png
1341839134.108666 rgb/1341839134.108666.png 1341839134.108678 depth/1341839134.108678.png
1341839134.145583 rgb/1341839134.145583.png 1341839134.145596 depth/1341839134.145596.png
1341839134.177037 rgb/1341839134.177037.png 1341839134.177059 depth/1341839134.177059.png
1341839134.208585 rgb/1341839134.208585.png 1341839134.208602 depth/1341839134.208602.png
1341839134.245077 rgb/1341839134.245077.png 1341839134.245208 depth/1341839134.245208.png
1341839134.276660 rgb/1341839134.276660.png 1341839134.276724 depth/1341839134.276724.png
1341839134.344596 rgb/1341839134.344596.png 1341839134.344691 depth/1341839134.344691.png
1341839134.405658 rgb/1341839134.405658.png 1341839134.405677 depth/1341839134.405677.png
1341839134.437582 rgb/1341839134.437582.png 1341839134.437603 depth/1341839134.437603.png
1341839134.473570 rgb/1341839134.473570.png 1341839134.473580 depth/1341839134.473580.png
1341839134.505576 rgb/1341839134.505576.png 1341839134.505609 depth/1341839134.505609.png
1341839134.537527 rgb/1341839134.537527.png 1341839134.537537 depth/1341839134.537537.png
1341839134.573575 rgb/1341839134.573575.png 1341839134.573591 depth/1341839134.573591.png
1341839134.605581 rgb/1341839134.605581.png 1341839134.605594 depth/1341839134.605594.png
1341839134.637613 rgb/1341839134.637613.png 1341839134.637630 depth/1341839134.637630.png
1341839134.673530 rgb/1341839134.673530.png 1341839134.673545 depth/1341839134.673545.png
1341839134.705768 rgb/1341839134.705768.png 1341839134.705781 depth/1341839134.705781.png
1341839134.741672 rgb/1341839134.741672.png 1341839134.741751 depth/1341839134.741751.png
1341839134.773479 rgb/1341839134.773479.png 1341839134.773494 depth/1341839134.773494.png
1341839134.805757 rgb/1341839134.805757.png 1341839134.805770 depth/1341839134.805770.png
1341839134.841632 rgb/1341839134.841632.png 1341839134.841655 depth/1341839134.841655.png
1341839134.873616 rgb/1341839134.873616.png 1341839134.873632 depth/1341839134.873632.png
1341839134.905696 rgb/1341839134.905696.png 1341839134.905704 depth/1341839134.905704.png
1341839134.941552 rgb/1341839134.941552.png 1341839134.941561 depth/1341839134.941561.png
1341839134.974666 rgb/1341839134.974666.png 1341839134.974739 depth/1341839134.974739.png
1341839135.009601 rgb/1341839135.009601.png 1341839135.009614 depth/1341839135.009614.png
1341839135.042135 rgb/1341839135.042135.png 1341839135.042147 depth/1341839135.042147.png
1341839135.073504 rgb/1341839135.073504.png 1341839135.073516 depth/1341839135.073516.png
1341839135.109696 rgb/1341839135.109696.png 1341839135.109714 depth/1341839135.109714.png
1341839135.141720 rgb/1341839135.141720.png 1341839135.141729 depth/1341839135.141729.png
1341839135.173566 rgb/1341839135.173566.png 1341839135.173615 depth/1341839135.173615.png
1341839135.209553 rgb/1341839135.209553.png 1341839135.209575 depth/1341839135.209575.png
1341839135.241688 rgb/1341839135.241688.png 1341839135.241697 depth/1341839135.241697.png
1341839135.277641 rgb/1341839135.277641.png 1341839135.277681 depth/1341839135.277681.png
1341839135.309842 rgb/1341839135.309842.png 1341839135.310691 depth/1341839135.310691.png
1341839135.341555 rgb/1341839135.341555.png 1341839135.341637 depth/1341839135.341637.png
1341839135.377558 rgb/1341839135.377558.png 1341839135.378308 depth/1341839135.378308.png
1341839135.409554 rgb/1341839135.409554.png 1341839135.409570 depth/1341839135.409570.png
1341839135.441588 rgb/1341839135.441588.png 1341839135.441604 depth/1341839135.441604.png
1341839135.477530 rgb/1341839135.477530.png 1341839135.477542 depth/1341839135.477542.png
1341839135.509758 rgb/1341839135.509758.png 1341839135.509777 depth/1341839135.509777.png
1341839135.545510 rgb/1341839135.545510.png 1341839135.545525 depth/1341839135.545525.png
1341839135.577577 rgb/1341839135.577577.png 1341839135.577594 depth/1341839135.577594.png
1341839135.609596 rgb/1341839135.609596.png 1341839135.609617 depth/1341839135.609617.png
1341839135.645470 rgb/1341839135.645470.png 1341839135.645480 depth/1341839135.645480.png
1341839135.677567 rgb/1341839135.677567.png 1341839135.677577 depth/1341839135.677577.png
1341839135.713508 rgb/1341839135.713508.png 1341839135.713519 depth/1341839135.713519.png
1341839135.745626 rgb/1341839135.745626.png 1341839135.745644 depth/1341839135.745644.png
1341839135.777556 rgb/1341839135.777556.png 1341839135.777565 depth/1341839135.777565.png
1341839135.813582 rgb/1341839135.813582.png 1341839135.813599 depth/1341839135.813599.png
1341839135.845539 rgb/1341839135.845539.png 1341839135.845556 depth/1341839135.845556.png
1341839135.877786 rgb/1341839135.877786.png 1341839135.877808 depth/1341839135.877808.png
1341839135.913620 rgb/1341839135.913620.png 1341839135.913634 depth/1341839135.913634.png
1341839135.945920 rgb/1341839135.945920.png 1341839135.947125 depth/1341839135.947125.png
1341839135.981913 rgb/1341839135.981913.png 1341839135.981941 depth/1341839135.981941.png
1341839136.014297 rgb/1341839136.014297.png 1341839136.014341 depth/1341839136.014341.png
1341839136.059226 rgb/1341839136.059226.png 1341839136.062945 depth/1341839136.062945.png
1341839136.120606 rgb/1341839136.120606.png 1341839136.120805 depth/1341839136.120805.png
1341839136.181673 rgb/1341839136.181673.png 1341839136.181696 depth/1341839136.181696.png
1341839136.214507 rgb/1341839136.214507.png 1341839136.215196 depth/1341839136.215196.png
1341839136.249624 rgb/1341839136.249624.png 1341839136.249642 depth/1341839136.249642.png
1341839136.281495 rgb/1341839136.281495.png 1341839136.281541 depth/1341839136.281541.png
1341839136.314066 rgb/1341839136.314066.png 1341839136.314093 depth/1341839136.314093.png
1341839136.349787 rgb/1341839136.349787.png 1341839136.349833 depth/1341839136.349833.png
1341839136.388618 rgb/1341839136.388618.png 1341839136.388647 depth/1341839136.388647.png
1341839136.449733 rgb/1341839136.449733.png 1341839136.449782 depth/1341839136.449782.png
1341839136.481697 rgb/1341839136.481697.png 1341839136.481996 depth/1341839136.481996.png
1341839136.517624 rgb/1341839136.517624.png 1341839136.518264 depth/1341839136.518264.png
1341839136.549505 rgb/1341839136.549505.png 1341839136.549533 depth/1341839136.549533.png
1341839136.581632 rgb/1341839136.581632.png 1341839136.581692 depth/1341839136.581692.png
1341839136.617613 rgb/1341839136.617613.png 1341839136.617621 depth/1341839136.617621.png
1341839136.649571 rgb/1341839136.649571.png 1341839136.649580 depth/1341839136.649580.png
1341839136.685554 rgb/1341839136.685554.png 1341839136.685653 depth/1341839136.685653.png
1341839136.717527 rgb/1341839136.717527.png 1341839136.717542 depth/1341839136.717542.png
1341839136.749496 rgb/1341839136.749496.png 1341839136.749506 depth/1341839136.749506.png
1341839136.785674 rgb/1341839136.785674.png 1341839136.785703 depth/1341839136.785703.png
1341839136.817542 rgb/1341839136.817542.png 1341839136.817555 depth/1341839136.817555.png
1341839136.849615 rgb/1341839136.849615.png 1341839136.849622 depth/1341839136.849622.png
1341839136.892657 rgb/1341839136.892657.png 1341839136.892705 depth/1341839136.892705.png
1341839136.953615 rgb/1341839136.953615.png 1341839136.953652 depth/1341839136.953652.png
1341839136.985942 rgb/1341839136.985942.png 1341839136.986038 depth/1341839136.986038.png
1341839137.017616 rgb/1341839137.017616.png 1341839137.017720 depth/1341839137.017720.png
1341839137.053572 rgb/1341839137.053572.png 1341839137.053657 depth/1341839137.053657.png
1341839137.085843 rgb/1341839137.085843.png 1341839137.086406 depth/1341839137.086406.png
1341839137.117537 rgb/1341839137.117537.png 1341839137.117619 depth/1341839137.117619.png
1341839137.153707 rgb/1341839137.153707.png 1341839137.153722 depth/1341839137.153722.png
1341839137.186296 rgb/1341839137.186296.png 1341839137.186313 depth/1341839137.186313.png
1341839137.221759 rgb/1341839137.221759.png 1341839137.221832 depth/1341839137.221832.png
1341839137.253565 rgb/1341839137.253565.png 1341839137.253576 depth/1341839137.253576.png
1341839137.285736 rgb/1341839137.285736.png 1341839137.285764 depth/1341839137.285764.png
1341839137.321642 rgb/1341839137.321642.png 1341839137.321686 depth/1341839137.321686.png
1341839137.353692 rgb/1341839137.353692.png 1341839137.353712 depth/1341839137.353712.png
1341839137.386256 rgb/1341839137.386256.png 1341839137.386271 depth/1341839137.386271.png
1341839137.421671 rgb/1341839137.421671.png 1341839137.421704 depth/1341839137.421704.png
1341839137.453657 rgb/1341839137.453657.png 1341839137.453673 depth/1341839137.453673.png
1341839137.489830 rgb/1341839137.489830.png 1341839137.490198 depth/1341839137.490198.png
1341839137.521652 rgb/1341839137.521652.png 1341839137.522084 depth/1341839137.522084.png
1341839137.553558 rgb/1341839137.553558.png 1341839137.553568 depth/1341839137.553568.png
1341839137.592577 rgb/1341839137.592577.png 1341839137.592649 depth/1341839137.592649.png
1341839137.628551 rgb/1341839137.628551.png 1341839137.628567 depth/1341839137.628567.png
1341839137.660598 rgb/1341839137.660598.png 1341839137.660617 depth/1341839137.660617.png
1341839137.692612 rgb/1341839137.692612.png 1341839137.692623 depth/1341839137.692623.png
1341839137.728532 rgb/1341839137.728532.png 1341839137.728545 depth/1341839137.728545.png
1341839137.760497 rgb/1341839137.760497.png 1341839137.760532 depth/1341839137.760532.png
1341839137.796681 rgb/1341839137.796681.png 1341839137.797171 depth/1341839137.797171.png
1341839137.828611 rgb/1341839137.828611.png 1341839137.828636 depth/1341839137.828636.png
1341839137.860523 rgb/1341839137.860523.png 1341839137.860532 depth/1341839137.860532.png
1341839137.896603 rgb/1341839137.896603.png 1341839137.896632 depth/1341839137.896632.png
1341839137.928510 rgb/1341839137.928510.png 1341839137.928525 depth/1341839137.928525.png
1341839137.964534 rgb/1341839137.964534.png 1341839137.964556 depth/1341839137.964556.png
1341839137.996524 rgb/1341839137.996524.png 1341839137.996611 depth/1341839137.996611.png
1341839138.028640 rgb/1341839138.028640.png 1341839138.028652 depth/1341839138.028652.png
1341839138.064541 rgb/1341839138.064541.png 1341839138.064555 depth/1341839138.064555.png
1341839138.096479 rgb/1341839138.096479.png 1341839138.096493 depth/1341839138.096493.png
1341839138.132550 rgb/1341839138.132550.png 1341839138.132565 depth/1341839138.132565.png
1341839138.164623 rgb/1341839138.164623.png 1341839138.164634 depth/1341839138.164634.png
1341839138.196431 rgb/1341839138.196431.png 1341839138.196452 depth/1341839138.196452.png
1341839138.232704 rgb/1341839138.232704.png 1341839138.232713 depth/1341839138.232713.png
1341839138.264578 rgb/1341839138.264578.png 1341839138.264590 depth/1341839138.264590.png
1341839138.300697 rgb/1341839138.300697.png 1341839138.300786 depth/1341839138.300786.png
1341839138.332541 rgb/1341839138.332541.png 1341839138.332563 depth/1341839138.332563.png
1341839138.364517 rgb/1341839138.364517.png 1341839138.364600 depth/1341839138.364600.png
1341839138.400834 rgb/1341839138.400834.png 1341839138.400865 depth/1341839138.400865.png
1341839138.432562 rgb/1341839138.432562.png 1341839138.432578 depth/1341839138.432578.png
1341839138.469017 rgb/1341839138.469017.png 1341839138.469050 depth/1341839138.469050.png
1341839138.500623 rgb/1341839138.500623.png 1341839138.500638 depth/1341839138.500638.png
1341839138.532584 rgb/1341839138.532584.png 1341839138.532604 depth/1341839138.532604.png
1341839138.568521 rgb/1341839138.568521.png 1341839138.568539 depth/1341839138.568539.png
1341839138.600559 rgb/1341839138.600559.png 1341839138.600568 depth/1341839138.600568.png
1341839138.637679 rgb/1341839138.637679.png 1341839138.637699 depth/1341839138.637699.png
1341839138.668579 rgb/1341839138.668579.png 1341839138.668589 depth/1341839138.668589.png
1341839138.700570 rgb/1341839138.700570.png 1341839138.700581 depth/1341839138.700581.png
1341839138.736618 rgb/1341839138.736618.png 1341839138.736629 depth/1341839138.736629.png
1341839138.768580 rgb/1341839138.768580.png 1341839138.768589 depth/1341839138.768589.png
1341839138.800591 rgb/1341839138.800591.png 1341839138.800600 depth/1341839138.800600.png
1341839138.836668 rgb/1341839138.836668.png 1341839138.836676 depth/1341839138.836676.png
1341839138.868631 rgb/1341839138.868631.png 1341839138.868645 depth/1341839138.868645.png
1341839138.900591 rgb/1341839138.900591.png 1341839138.900602 depth/1341839138.900602.png
1341839138.936751 rgb/1341839138.936751.png 1341839138.936770 depth/1341839138.936770.png
1341839138.968925 rgb/1341839138.968925.png 1341839138.968948 depth/1341839138.968948.png
1341839139.004685 rgb/1341839139.004685.png 1341839139.004813 depth/1341839139.004813.png
1341839139.036835 rgb/1341839139.036835.png 1341839139.036847 depth/1341839139.036847.png
1341839139.069010 rgb/1341839139.069010.png 1341839139.070300 depth/1341839139.070300.png
1341839139.105164 rgb/1341839139.105164.png 1341839139.106306 depth/1341839139.106306.png
1341839139.137964 rgb/1341839139.137964.png 1341839139.138489 depth/1341839139.138489.png
1341839139.168993 rgb/1341839139.168993.png 1341839139.169907 depth/1341839139.169907.png
1341839139.208632 rgb/1341839139.208632.png 1341839139.209438 depth/1341839139.209438.png
1341839139.237233 rgb/1341839139.237233.png 1341839139.238326 depth/1341839139.238326.png
1341839139.269740 rgb/1341839139.269740.png 1341839139.271376 depth/1341839139.271376.png
1341839139.305090 rgb/1341839139.305090.png 1341839139.305552 depth/1341839139.305552.png
1341839139.336872 rgb/1341839139.336872.png 1341839139.337515 depth/1341839139.337515.png
1341839139.404779 rgb/1341839139.404779.png 1341839139.405486 depth/1341839139.405486.png
1341839139.436967 rgb/1341839139.436967.png 1341839139.437404 depth/1341839139.437404.png
1341839139.479384 rgb/1341839139.479384.png 1341839139.480479 depth/1341839139.480479.png
1341839139.504961 rgb/1341839139.504961.png 1341839139.505005 depth/1341839139.505005.png
1341839139.572716 rgb/1341839139.572716.png 1341839139.572945 depth/1341839139.572945.png
1341839139.633776 rgb/1341839139.633776.png 1341839139.633799 depth/1341839139.633799.png
1341839139.665625 rgb/1341839139.665625.png 1341839139.665653 depth/1341839139.665653.png
1341839139.701587 rgb/1341839139.701587.png 1341839139.701596 depth/1341839139.701596.png
1341839139.733553 rgb/1341839139.733553.png 1341839139.733611 depth/1341839139.733611.png
1341839139.765553 rgb/1341839139.765553.png 1341839139.765574 depth/1341839139.765574.png
1341839139.801543 rgb/1341839139.801543.png 1341839139.801605 depth/1341839139.801605.png
1341839139.833756 rgb/1341839139.833756.png 1341839139.833768 depth/1341839139.833768.png
1341839139.865591 rgb/1341839139.865591.png 1341839139.865601 depth/1341839139.865601.png
1341839139.901631 rgb/1341839139.901631.png 1341839139.901643 depth/1341839139.901643.png
1341839139.933716 rgb/1341839139.933716.png 1341839139.933753 depth/1341839139.933753.png
1341839139.969603 rgb/1341839139.969603.png 1341839139.969635 depth/1341839139.969635.png
1341839140.001567 rgb/1341839140.001567.png 1341839140.001587 depth/1341839140.001587.png
1341839140.033569 rgb/1341839140.033569.png 1341839140.033598 depth/1341839140.033598.png
1341839140.069602 rgb/1341839140.069602.png 1341839140.069614 depth/1341839140.069614.png
1341839140.101607 rgb/1341839140.101607.png 1341839140.101621 depth/1341839140.101621.png
1341839140.137593 rgb/1341839140.137593.png 1341839140.137615 depth/1341839140.137615.png
1341839140.169583 rgb/1341839140.169583.png 1341839140.169652 depth/1341839140.169652.png
1341839140.201678 rgb/1341839140.201678.png 1341839140.201687 depth/1341839140.201687.png
1341839140.237641 rgb/1341839140.237641.png 1341839140.238134 depth/1341839140.238134.png
1341839140.269632 rgb/1341839140.269632.png 1341839140.269703 depth/1341839140.269703.png
1341839140.301538 rgb/1341839140.301538.png 1341839140.301552 depth/1341839140.301552.png
1341839140.337608 rgb/1341839140.337608.png 1341839140.338185 depth/1341839140.338185.png
1341839140.369503 rgb/1341839140.369503.png 1341839140.369514 depth/1341839140.369514.png
1341839140.405652 rgb/1341839140.405652.png 1341839140.405699 depth/1341839140.405699.png
1341839140.437622 rgb/1341839140.437622.png 1341839140.437643 depth/1341839140.437643.png
1341839140.469802 rgb/1341839140.469802.png 1341839140.469827 depth/1341839140.469827.png
1341839140.505600 rgb/1341839140.505600.png 1341839140.505608 depth/1341839140.505608.png
1341839140.537508 rgb/1341839140.537508.png 1341839140.537516 depth/1341839140.537516.png
1341839140.569631 rgb/1341839140.569631.png 1341839140.569669 depth/1341839140.569669.png
1341839140.605614 rgb/1341839140.605614.png 1341839140.605628 depth/1341839140.605628.png
1341839140.637520 rgb/1341839140.637520.png 1341839140.637540 depth/1341839140.637540.png
1341839140.673589 rgb/1341839140.673589.png 1341839140.673608 depth/1341839140.673608.png
1341839140.705526 rgb/1341839140.705526.png 1341839140.705539 depth/1341839140.705539.png
1341839140.737690 rgb/1341839140.737690.png 1341839140.737704 depth/1341839140.737704.png
1341839140.780691 rgb/1341839140.780691.png 1341839140.780735 depth/1341839140.780735.png
1341839140.837561 rgb/1341839140.837561.png 1341839140.837578 depth/1341839140.837578.png
1341839140.873616 rgb/1341839140.873616.png 1341839140.873620 depth/1341839140.873620.png
1341839140.905496 rgb/1341839140.905496.png 1341839140.905503 depth/1341839140.905503.png
1341839140.941764 rgb/1341839140.941764.png 1341839140.941788 depth/1341839140.941788.png
1341839140.973483 rgb/1341839140.973483.png 1341839140.973496 depth/1341839140.973496.png
1341839141.005687 rgb/1341839141.005687.png 1341839141.005702 depth/1341839141.005702.png
1341839141.041564 rgb/1341839141.041564.png 1341839141.041580 depth/1341839141.041580.png
1341839141.074063 rgb/1341839141.074063.png 1341839141.074113 depth/1341839141.074113.png
1341839141.110271 rgb/1341839141.110271.png 1341839141.111227 depth/1341839141.111227.png
1341839141.141854 rgb/1341839141.141854.png 1341839141.143041 depth/1341839141.143041.png
1341839141.176858 rgb/1341839141.176858.png 1341839141.178116 depth/1341839141.178116.png
1341839141.209658 rgb/1341839141.209658.png 1341839141.210052 depth/1341839141.210052.png
1341839141.241623 rgb/1341839141.241623.png 1341839141.241640 depth/1341839141.241640.png
1341839141.273659 rgb/1341839141.273659.png 1341839141.273677 depth/1341839141.273677.png
1341839141.309576 rgb/1341839141.309576.png 1341839141.309585 depth/1341839141.309585.png
1341839141.341687 rgb/1341839141.341687.png 1341839141.341778 depth/1341839141.341778.png
1341839141.378026 rgb/1341839141.378026.png 1341839141.378158 depth/1341839141.378158.png
1341839141.409623 rgb/1341839141.409623.png 1341839141.409665 depth/1341839141.409665.png
1341839141.441571 rgb/1341839141.441571.png 1341839141.441583 depth/1341839141.441583.png
1341839141.477635 rgb/1341839141.477635.png 1341839141.477651 depth/1341839141.477651.png
1341839141.509696 rgb/1341839141.509696.png 1341839141.509729 depth/1341839141.509729.png
1341839141.541659 rgb/1341839141.541659.png 1341839141.541710 depth/1341839141.541710.png
1341839141.577526 rgb/1341839141.577526.png 1341839141.577573 depth/1341839141.577573.png
1341839141.645706 rgb/1341839141.645706.png 1341839141.645797 depth/1341839141.645797.png
1341839141.677487 rgb/1341839141.677487.png 1341839141.677499 depth/1341839141.677499.png
1341839141.709572 rgb/1341839141.709572.png 1341839141.709590 depth/1341839141.709590.png
1341839141.745638 rgb/1341839141.745638.png 1341839141.745654 depth/1341839141.745654.png
1341839141.777895 rgb/1341839141.777895.png 1341839141.778356 depth/1341839141.778356.png
1341839141.809561 rgb/1341839141.809561.png 1341839141.809573 depth/1341839141.809573.png
1341839141.845701 rgb/1341839141.845701.png 1341839141.845720 depth/1341839141.845720.png
1341839141.877530 rgb/1341839141.877530.png 1341839141.877549 depth/1341839141.877549.png
1341839141.913569 rgb/1341839141.913569.png 1341839141.913591 depth/1341839141.913591.png
1341839141.945636 rgb/1341839141.945636.png 1341839141.945649 depth/1341839141.945649.png
1341839141.977668 rgb/1341839141.977668.png 1341839141.977695 depth/1341839141.977695.png
1341839142.013466 rgb/1341839142.013466.png 1341839142.013492 depth/1341839142.013492.png
1341839142.048866 rgb/1341839142.048866.png 1341839142.048888 depth/1341839142.048888.png
1341839142.116693 rgb/1341839142.116693.png 1341839142.116751 depth/1341839142.116751.png
1341839142.181588 rgb/1341839142.181588.png 1341839142.181631 depth/1341839142.181631.png
1341839142.213523 rgb/1341839142.213523.png 1341839142.213533 depth/1341839142.213533.png
1341839142.245657 rgb/1341839142.245657.png 1341839142.245678 depth/1341839142.245678.png
1341839142.281484 rgb/1341839142.281484.png 1341839142.281493 depth/1341839142.281493.png
1341839142.313501 rgb/1341839142.313501.png 1341839142.313509 depth/1341839142.313509.png
1341839142.349595 rgb/1341839142.349595.png 1341839142.349620 depth/1341839142.349620.png
1341839142.413736 rgb/1341839142.413736.png 1341839142.413767 depth/1341839142.413767.png
1341839142.449600 rgb/1341839142.449600.png 1341839142.449618 depth/1341839142.449618.png
1341839142.481586 rgb/1341839142.481586.png 1341839142.481606 depth/1341839142.481606.png
1341839142.513495 rgb/1341839142.513495.png 1341839142.513509 depth/1341839142.513509.png
1341839142.549621 rgb/1341839142.549621.png 1341839142.549634 depth/1341839142.549634.png
1341839142.581646 rgb/1341839142.581646.png 1341839142.582088 depth/1341839142.582088.png
1341839142.617733 rgb/1341839142.617733.png 1341839142.618319 depth/1341839142.618319.png
1341839142.649501 rgb/1341839142.649501.png 1341839142.649517 depth/1341839142.649517.png
1341839142.681490 rgb/1341839142.681490.png 1341839142.681506 depth/1341839142.681506.png
1341839142.717648 rgb/1341839142.717648.png 1341839142.717673 depth/1341839142.717673.png
1341839142.749655 rgb/1341839142.749655.png 1341839142.750498 depth/1341839142.750498.png
1341839142.781698 rgb/1341839142.781698.png 1341839142.781971 depth/1341839142.781971.png
1341839142.817748 rgb/1341839142.817748.png 1341839142.817777 depth/1341839142.817777.png
1341839142.849646 rgb/1341839142.849646.png 1341839142.849670 depth/1341839142.849670.png
1341839142.885615 rgb/1341839142.885615.png 1341839142.885630 depth/1341839142.885630.png
1341839142.917485 rgb/1341839142.917485.png 1341839142.917510 depth/1341839142.917510.png
1341839142.949726 rgb/1341839142.949726.png 1341839142.949748 depth/1341839142.949748.png
1341839142.985900 rgb/1341839142.985900.png 1341839142.985931 depth/1341839142.985931.png
1341839143.025376 rgb/1341839143.025376.png 1341839143.026222 depth/1341839143.026222.png
1341839143.056750 rgb/1341839143.056750.png 1341839143.056780 depth/1341839143.056780.png
1341839143.092610 rgb/1341839143.092610.png 1341839143.092659 depth/1341839143.092659.png
1341839143.124560 rgb/1341839143.124560.png 1341839143.124570 depth/1341839143.124570.png
1341839143.160701 rgb/1341839143.160701.png 1341839143.161188 depth/1341839143.161188.png
1341839143.224815 rgb/1341839143.224815.png 1341839143.224874 depth/1341839143.224874.png
1341839143.285789 rgb/1341839143.285789.png 1341839143.285858 depth/1341839143.285858.png
1341839143.321671 rgb/1341839143.321671.png 1341839143.321694 depth/1341839143.321694.png
1341839143.353517 rgb/1341839143.353517.png 1341839143.353534 depth/1341839143.353534.png
1341839143.385603 rgb/1341839143.385603.png 1341839143.385625 depth/1341839143.385625.png
1341839143.421529 rgb/1341839143.421529.png 1341839143.421572 depth/1341839143.421572.png
1341839143.453645 rgb/1341839143.453645.png 1341839143.453688 depth/1341839143.453688.png
1341839143.485734 rgb/1341839143.485734.png 1341839143.485756 depth/1341839143.485756.png
1341839143.521668 rgb/1341839143.521668.png 1341839143.521684 depth/1341839143.521684.png
1341839143.553630 rgb/1341839143.553630.png 1341839143.553660 depth/1341839143.553660.png
1341839143.590154 rgb/1341839143.590154.png 1341839143.590166 depth/1341839143.590166.png
1341839143.621854 rgb/1341839143.621854.png 1341839143.621867 depth/1341839143.621867.png
1341839143.653546 rgb/1341839143.653546.png 1341839143.653560 depth/1341839143.653560.png
1341839143.689669 rgb/1341839143.689669.png 1341839143.689685 depth/1341839143.689685.png
1341839143.721563 rgb/1341839143.721563.png 1341839143.721578 depth/1341839143.721578.png
1341839143.753557 rgb/1341839143.753557.png 1341839143.753575 depth/1341839143.753575.png
1341839143.789597 rgb/1341839143.789597.png 1341839143.789627 depth/1341839143.789627.png
1341839143.821488 rgb/1341839143.821488.png 1341839143.821505 depth/1341839143.821505.png
1341839143.857691 rgb/1341839143.857691.png 1341839143.857712 depth/1341839143.857712.png
1341839143.889668 rgb/1341839143.889668.png 1341839143.889711 depth/1341839143.889711.png
1341839143.921613 rgb/1341839143.921613.png 1341839143.921625 depth/1341839143.921625.png
1341839143.957679 rgb/1341839143.957679.png 1341839143.957695 depth/1341839143.957695.png
1341839143.989692 rgb/1341839143.989692.png 1341839143.989707 depth/1341839143.989707.png
1341839144.021612 rgb/1341839144.021612.png 1341839144.021623 depth/1341839144.021623.png
1341839144.057581 rgb/1341839144.057581.png 1341839144.057682 depth/1341839144.057682.png
1341839144.089682 rgb/1341839144.089682.png 1341839144.090414 depth/1341839144.090414.png
1341839144.125588 rgb/1341839144.125588.png 1341839144.125627 depth/1341839144.125627.png
1341839144.157579 rgb/1341839144.157579.png 1341839144.157593 depth/1341839144.157593.png
1341839144.189633 rgb/1341839144.189633.png 1341839144.189686 depth/1341839144.189686.png
1341839144.225642 rgb/1341839144.225642.png 1341839144.225712 depth/1341839144.225712.png
1341839144.257760 rgb/1341839144.257760.png 1341839144.257782 depth/1341839144.257782.png
1341839144.289779 rgb/1341839144.289779.png 1341839144.289825 depth/1341839144.289825.png
1341839144.325641 rgb/1341839144.325641.png 1341839144.325658 depth/1341839144.325658.png
1341839144.357603 rgb/1341839144.357603.png 1341839144.357629 depth/1341839144.357629.png
1341839144.393630 rgb/1341839144.393630.png 1341839144.393670 depth/1341839144.393670.png
1341839144.425526 rgb/1341839144.425526.png 1341839144.425538 depth/1341839144.425538.png
1341839144.457696 rgb/1341839144.457696.png 1341839144.458734 depth/1341839144.458734.png
1341839144.493799 rgb/1341839144.493799.png 1341839144.493809 depth/1341839144.493809.png
1341839144.525996 rgb/1341839144.525996.png 1341839144.526031 depth/1341839144.526031.png
1341839144.561696 rgb/1341839144.561696.png 1341839144.561705 depth/1341839144.561705.png
1341839144.593602 rgb/1341839144.593602.png 1341839144.594287 depth/1341839144.594287.png
1341839144.627771 rgb/1341839144.627771.png 1341839144.627802 depth/1341839144.627802.png
1341839144.661818 rgb/1341839144.661818.png 1341839144.663741 depth/1341839144.663741.png
1341839144.732548 rgb/1341839144.732548.png 1341839144.732583 depth/1341839144.732583.png
1341839144.793602 rgb/1341839144.793602.png 1341839144.793614 depth/1341839144.793614.png
1341839144.829602 rgb/1341839144.829602.png 1341839144.829617 depth/1341839144.829617.png
1341839144.861614 rgb/1341839144.861614.png 1341839144.861628 depth/1341839144.861628.png
1341839144.893704 rgb/1341839144.893704.png 1341839144.893753 depth/1341839144.893753.png
1341839144.929498 rgb/1341839144.929498.png 1341839144.929511 depth/1341839144.929511.png
1341839144.961563 rgb/1341839144.961563.png 1341839144.961580 depth/1341839144.961580.png
1341839144.993581 rgb/1341839144.993581.png 1341839144.993599 depth/1341839144.993599.png
1341839145.029623 rgb/1341839145.029623.png 1341839145.029664 depth/1341839145.029664.png
1341839145.061626 rgb/1341839145.061626.png 1341839145.061641 depth/1341839145.061641.png
1341839145.097529 rgb/1341839145.097529.png 1341839145.097551 depth/1341839145.097551.png
1341839145.129540 rgb/1341839145.129540.png 1341839145.129551 depth/1341839145.129551.png
1341839145.161548 rgb/1341839145.161548.png 1341839145.161615 depth/1341839145.161615.png
1341839145.197472 rgb/1341839145.197472.png 1341839145.197504 depth/1341839145.197504.png
1341839145.229600 rgb/1341839145.229600.png 1341839145.230231 depth/1341839145.230231.png
1341839145.262518 rgb/1341839145.262518.png 1341839145.262530 depth/1341839145.262530.png
1341839145.297552 rgb/1341839145.297552.png 1341839145.297620 depth/1341839145.297620.png
1341839145.329591 rgb/1341839145.329591.png 1341839145.329622 depth/1341839145.329622.png
================================================
FILE: Examples/RGB-D/associations/fr3_str_tex_near.txt
================================================
1341839327.392692 rgb/1341839327.392692.png 1341839327.392719 depth/1341839327.392719.png
1341839327.424683 rgb/1341839327.424683.png 1341839327.424732 depth/1341839327.424732.png
1341839327.460744 rgb/1341839327.460744.png 1341839327.460763 depth/1341839327.460763.png
1341839327.492713 rgb/1341839327.492713.png 1341839327.492724 depth/1341839327.492724.png
1341839327.524801 rgb/1341839327.524801.png 1341839327.524824 depth/1341839327.524824.png
1341839327.560844 rgb/1341839327.560844.png 1341839327.560867 depth/1341839327.560867.png
1341839327.592601 rgb/1341839327.592601.png 1341839327.592616 depth/1341839327.592616.png
1341839327.624910 rgb/1341839327.624910.png 1341839327.625438 depth/1341839327.625438.png
1341839327.660734 rgb/1341839327.660734.png 1341839327.660773 depth/1341839327.660773.png
1341839327.692726 rgb/1341839327.692726.png 1341839327.693149 depth/1341839327.693149.png
1341839327.728746 rgb/1341839327.728746.png 1341839327.728770 depth/1341839327.728770.png
1341839327.760684 rgb/1341839327.760684.png 1341839327.760693 depth/1341839327.760693.png
1341839327.792848 rgb/1341839327.792848.png 1341839327.792870 depth/1341839327.792870.png
1341839327.828735 rgb/1341839327.828735.png 1341839327.828764 depth/1341839327.828764.png
1341839327.860775 rgb/1341839327.860775.png 1341839327.861088 depth/1341839327.861088.png
1341839327.892707 rgb/1341839327.892707.png 1341839327.892736 depth/1341839327.892736.png
1341839327.928885 rgb/1341839327.928885.png 1341839327.928913 depth/1341839327.928913.png
1341839327.960681 rgb/1341839327.960681.png 1341839327.960709 depth/1341839327.960709.png
1341839327.992694 rgb/1341839327.992694.png 1341839327.993314 depth/1341839327.993314.png
1341839328.028635 rgb/1341839328.028635.png 1341839328.028650 depth/1341839328.028650.png
1341839328.060669 rgb/1341839328.060669.png 1341839328.060694 depth/1341839328.060694.png
1341839328.096628 rgb/1341839328.096628.png 1341839328.096649 depth/1341839328.096649.png
1341839328.128788 rgb/1341839328.128788.png 1341839328.128874 depth/1341839328.128874.png
1341839328.160826 rgb/1341839328.160826.png 1341839328.160854 depth/1341839328.160854.png
1341839328.196725 rgb/1341839328.196725.png 1341839328.196745 depth/1341839328.196745.png
1341839328.228674 rgb/1341839328.228674.png 1341839328.229156 depth/1341839328.229156.png
1341839328.260676 rgb/1341839328.260676.png 1341839328.261208 depth/1341839328.261208.png
1341839328.296667 rgb/1341839328.296667.png 1341839328.297137 depth/1341839328.297137.png
1341839328.328755 rgb/1341839328.328755.png 1341839328.328784 depth/1341839328.328784.png
1341839328.360635 rgb/1341839328.360635.png 1341839328.360665 depth/1341839328.360665.png
1341839328.396819 rgb/1341839328.396819.png 1341839328.396926 depth/1341839328.396926.png
1341839328.428710 rgb/1341839328.428710.png 1341839328.429370 depth/1341839328.429370.png
1341839328.464835 rgb/1341839328.464835.png 1341839328.464846 depth/1341839328.464846.png
1341839328.496659 rgb/1341839328.496659.png 1341839328.496692 depth/1341839328.496692.png
1341839328.528673 rgb/1341839328.528673.png 1341839328.528687 depth/1341839328.528687.png
1341839328.564728 rgb/1341839328.564728.png 1341839328.564740 depth/1341839328.564740.png
1341839328.625878 rgb/1341839328.625878.png 1341839328.625940 depth/1341839328.625940.png
1341839328.657644 rgb/1341839328.657644.png 1341839328.657766 depth/1341839328.657766.png
1341839328.693566 rgb/1341839328.693566.png 1341839328.693593 depth/1341839328.693593.png
1341839328.725884 rgb/1341839328.725884.png 1341839328.726559 depth/1341839328.726559.png
1341839328.757668 rgb/1341839328.757668.png 1341839328.757898 depth/1341839328.757898.png
1341839328.793500 rgb/1341839328.793500.png 1341839328.793518 depth/1341839328.793518.png
1341839328.826689 rgb/1341839328.826689.png 1341839328.826770 depth/1341839328.826770.png
1341839328.861628 rgb/1341839328.861628.png 1341839328.861644 depth/1341839328.861644.png
1341839328.893838 rgb/1341839328.893838.png 1341839328.893849 depth/1341839328.893849.png
1341839328.925828 rgb/1341839328.925828.png 1341839328.925868 depth/1341839328.925868.png
1341839328.961597 rgb/1341839328.961597.png 1341839328.961613 depth/1341839328.961613.png
1341839328.993736 rgb/1341839328.993736.png 1341839328.993792 depth/1341839328.993792.png
1341839329.026046 rgb/1341839329.026046.png 1341839329.026055 depth/1341839329.026055.png
1341839329.061681 rgb/1341839329.061681.png 1341839329.062092 depth/1341839329.062092.png
1341839329.093651 rgb/1341839329.093651.png 1341839329.093661 depth/1341839329.093661.png
1341839329.129705 rgb/1341839329.129705.png 1341839329.129714 depth/1341839329.129714.png
1341839329.161766 rgb/1341839329.161766.png 1341839329.161805 depth/1341839329.161805.png
1341839329.193630 rgb/1341839329.193630.png 1341839329.193646 depth/1341839329.193646.png
1341839329.229958 rgb/1341839329.229958.png 1341839329.229989 depth/1341839329.229989.png
1341839329.261621 rgb/1341839329.261621.png 1341839329.261633 depth/1341839329.261633.png
1341839329.293826 rgb/1341839329.293826.png 1341839329.294019 depth/1341839329.294019.png
1341839329.330161 rgb/1341839329.330161.png 1341839329.330182 depth/1341839329.330182.png
1341839329.361576 rgb/1341839329.361576.png 1341839329.361588 depth/1341839329.361588.png
1341839329.397677 rgb/1341839329.397677.png 1341839329.397693 depth/1341839329.397693.png
1341839329.429794 rgb/1341839329.429794.png 1341839329.429824 depth/1341839329.429824.png
1341839329.462095 rgb/1341839329.462095.png 1341839329.462140 depth/1341839329.462140.png
1341839329.497776 rgb/1341839329.497776.png 1341839329.497817 depth/1341839329.497817.png
1341839329.529609 rgb/1341839329.529609.png 1341839329.529623 depth/1341839329.529623.png
1341839329.565820 rgb/1341839329.565820.png 1341839329.565832 depth/1341839329.565832.png
1341839329.597604 rgb/1341839329.597604.png 1341839329.597657 depth/1341839329.597657.png
1341839329.629668 rgb/1341839329.629668.png 1341839329.629682 depth/1341839329.629682.png
1341839329.665800 rgb/1341839329.665800.png 1341839329.665817 depth/1341839329.665817.png
1341839329.697644 rgb/1341839329.697644.png 1341839329.697655 depth/1341839329.697655.png
1341839329.729773 rgb/1341839329.729773.png 1341839329.729794 depth/1341839329.729794.png
1341839329.765624 rgb/1341839329.765624.png 1341839329.765645 depth/1341839329.765645.png
1341839329.797643 rgb/1341839329.797643.png 1341839329.797665 depth/1341839329.797665.png
1341839329.833722 rgb/1341839329.833722.png 1341839329.833742 depth/1341839329.833742.png
1341839329.865810 rgb/1341839329.865810.png 1341839329.865832 depth/1341839329.865832.png
1341839329.897566 rgb/1341839329.897566.png 1341839329.897578 depth/1341839329.897578.png
1341839329.933593 rgb/1341839329.933593.png 1341839329.933601 depth/1341839329.933601.png
1341839329.965703 rgb/1341839329.965703.png 1341839329.965721 depth/1341839329.965721.png
1341839329.997622 rgb/1341839329.997622.png 1341839329.997659 depth/1341839329.997659.png
1341839330.033691 rgb/1341839330.033691.png 1341839330.033740 depth/1341839330.033740.png
1341839330.065682 rgb/1341839330.065682.png 1341839330.065737 depth/1341839330.065737.png
1341839330.101720 rgb/1341839330.101720.png 1341839330.101744 depth/1341839330.101744.png
1341839330.133799 rgb/1341839330.133799.png 1341839330.133824 depth/1341839330.133824.png
1341839330.165594 rgb/1341839330.165594.png 1341839330.165634 depth/1341839330.165634.png
1341839330.201660 rgb/1341839330.201660.png 1341839330.201705 depth/1341839330.201705.png
1341839330.233709 rgb/1341839330.233709.png 1341839330.233722 depth/1341839330.233722.png
1341839330.265739 rgb/1341839330.265739.png 1341839330.266312 depth/1341839330.266312.png
1341839330.301821 rgb/1341839330.301821.png 1341839330.302347 depth/1341839330.302347.png
1341839330.333763 rgb/1341839330.333763.png 1341839330.333775 depth/1341839330.333775.png
1341839330.369586 rgb/1341839330.369586.png 1341839330.369606 depth/1341839330.369606.png
1341839330.401592 rgb/1341839330.401592.png 1341839330.401603 depth/1341839330.401603.png
1341839330.433755 rgb/1341839330.433755.png 1341839330.433788 depth/1341839330.433788.png
1341839330.469655 rgb/1341839330.469655.png 1341839330.469667 depth/1341839330.469667.png
1341839330.501951 rgb/1341839330.501951.png 1341839330.501975 depth/1341839330.501975.png
1341839330.533811 rgb/1341839330.533811.png 1341839330.533857 depth/1341839330.533857.png
1341839330.569658 rgb/1341839330.569658.png 1341839330.569675 depth/1341839330.569675.png
1341839330.601587 rgb/1341839330.601587.png 1341839330.601595 depth/1341839330.601595.png
1341839330.637700 rgb/1341839330.637700.png 1341839330.638143 depth/1341839330.638143.png
1341839330.669658 rgb/1341839330.669658.png 1341839330.669672 depth/1341839330.669672.png
1341839330.701704 rgb/1341839330.701704.png 1341839330.701788 depth/1341839330.701788.png
1341839330.737621 rgb/1341839330.737621.png 1341839330.737650 depth/1341839330.737650.png
1341839330.769669 rgb/1341839330.769669.png 1341839330.769683 depth/1341839330.769683.png
1341839330.805848 rgb/1341839330.805848.png 1341839330.805857 depth/1341839330.805857.png
1341839330.837580 rgb/1341839330.837580.png 1341839330.837591 depth/1341839330.837591.png
1341839330.869617 rgb/1341839330.869617.png 1341839330.869625 depth/1341839330.869625.png
1341839330.905589 rgb/1341839330.905589.png 1341839330.905598 depth/1341839330.905598.png
1341839330.937600 rgb/1341839330.937600.png 1341839330.937608 depth/1341839330.937608.png
1341839330.969715 rgb/1341839330.969715.png 1341839330.969732 depth/1341839330.969732.png
1341839331.005663 rgb/1341839331.005663.png 1341839331.005686 depth/1341839331.005686.png
1341839331.037575 rgb/1341839331.037575.png 1341839331.037590 depth/1341839331.037590.png
1341839331.073681 rgb/1341839331.073681.png 1341839331.073709 depth/1341839331.073709.png
1341839331.105674 rgb/1341839331.105674.png 1341839331.105691 depth/1341839331.105691.png
1341839331.137723 rgb/1341839331.137723.png 1341839331.137734 depth/1341839331.137734.png
1341839331.173604 rgb/1341839331.173604.png 1341839331.173665 depth/1341839331.173665.png
1341839331.206025 rgb/1341839331.206025.png 1341839331.206108 depth/1341839331.206108.png
1341839331.237569 rgb/1341839331.237569.png 1341839331.237591 depth/1341839331.237591.png
1341839331.273666 rgb/1341839331.273666.png 1341839331.273677 depth/1341839331.273677.png
1341839331.305627 rgb/1341839331.305627.png 1341839331.305666 depth/1341839331.305666.png
1341839331.341607 rgb/1341839331.341607.png 1341839331.341623 depth/1341839331.341623.png
1341839331.373735 rgb/1341839331.373735.png 1341839331.373753 depth/1341839331.373753.png
1341839331.405705 rgb/1341839331.405705.png 1341839331.405723 depth/1341839331.405723.png
1341839331.473794 rgb/1341839331.473794.png 1341839331.473871 depth/1341839331.473871.png
1341839331.505887 rgb/1341839331.505887.png 1341839331.505920 depth/1341839331.505920.png
1341839331.541633 rgb/1341839331.541633.png 1341839331.541699 depth/1341839331.541699.png
1341839331.573588 rgb/1341839331.573588.png 1341839331.573605 depth/1341839331.573605.png
1341839331.609760 rgb/1341839331.609760.png 1341839331.609775 depth/1341839331.609775.png
1341839331.641625 rgb/1341839331.641625.png 1341839331.641636 depth/1341839331.641636.png
1341839331.673616 rgb/1341839331.673616.png 1341839331.673645 depth/1341839331.673645.png
1341839331.709625 rgb/1341839331.709625.png 1341839331.709686 depth/1341839331.709686.png
1341839331.741634 rgb/1341839331.741634.png 1341839331.741643 depth/1341839331.741643.png
1341839331.777583 rgb/1341839331.777583.png 1341839331.777603 depth/1341839331.777603.png
1341839331.809615 rgb/1341839331.809615.png 1341839331.809647 depth/1341839331.809647.png
1341839331.841790 rgb/1341839331.841790.png 1341839331.841801 depth/1341839331.841801.png
1341839331.877680 rgb/1341839331.877680.png 1341839331.878215 depth/1341839331.878215.png
1341839331.909730 rgb/1341839331.909730.png 1341839331.909748 depth/1341839331.909748.png
1341839331.941711 rgb/1341839331.941711.png 1341839331.941725 depth/1341839331.941725.png
1341839331.977710 rgb/1341839331.977710.png 1341839331.977728 depth/1341839331.977728.png
1341839332.045792 rgb/1341839332.045792.png 1341839332.045816 depth/1341839332.045816.png
1341839332.077575 rgb/1341839332.077575.png 1341839332.077582 depth/1341839332.077582.png
1341839332.116871 rgb/1341839332.116871.png 1341839332.116893 depth/1341839332.116893.png
1341839332.152604 rgb/1341839332.152604.png 1341839332.152616 depth/1341839332.152616.png
1341839332.184662 rgb/1341839332.184662.png 1341839332.184678 depth/1341839332.184678.png
1341839332.216752 rgb/1341839332.216752.png 1341839332.216770 depth/1341839332.216770.png
1341839332.252770 rgb/1341839332.252770.png 1341839332.252784 depth/1341839332.252784.png
1341839332.284701 rgb/1341839332.284701.png 1341839332.284720 depth/1341839332.284720.png
1341839332.320752 rgb/1341839332.320752.png 1341839332.320763 depth/1341839332.320763.png
1341839332.352704 rgb/1341839332.352704.png 1341839332.352725 depth/1341839332.352725.png
1341839332.384789 rgb/1341839332.384789.png 1341839332.384802 depth/1341839332.384802.png
1341839332.420694 rgb/1341839332.420694.png 1341839332.420707 depth/1341839332.420707.png
1341839332.453030 rgb/1341839332.453030.png 1341839332.453040 depth/1341839332.453040.png
1341839332.484688 rgb/1341839332.484688.png 1341839332.484707 depth/1341839332.484707.png
1341839332.520706 rgb/1341839332.520706.png 1341839332.520728 depth/1341839332.520728.png
1341839332.552671 rgb/1341839332.552671.png 1341839332.552694 depth/1341839332.552694.png
1341839332.584673 rgb/1341839332.584673.png 1341839332.584689 depth/1341839332.584689.png
1341839332.620880 rgb/1341839332.620880.png 1341839332.620915 depth/1341839332.620915.png
1341839332.652689 rgb/1341839332.652689.png 1341839332.652728 depth/1341839332.652728.png
1341839332.688723 rgb/1341839332.688723.png 1341839332.688741 depth/1341839332.688741.png
1341839332.720653 rgb/1341839332.720653.png 1341839332.720665 depth/1341839332.720665.png
1341839332.752651 rgb/1341839332.752651.png 1341839332.752666 depth/1341839332.752666.png
1341839332.788721 rgb/1341839332.788721.png 1341839332.788766 depth/1341839332.788766.png
1341839332.820842 rgb/1341839332.820842.png 1341839332.820854 depth/1341839332.820854.png
1341839332.852685 rgb/1341839332.852685.png 1341839332.852703 depth/1341839332.852703.png
1341839332.888848 rgb/1341839332.888848.png 1341839332.889321 depth/1341839332.889321.png
1341839332.920995 rgb/1341839332.920995.png 1341839332.921019 depth/1341839332.921019.png
1341839332.952682 rgb/1341839332.952682.png 1341839332.952691 depth/1341839332.952691.png
1341839332.988738 rgb/1341839332.988738.png 1341839332.988751 depth/1341839332.988751.png
1341839333.020623 rgb/1341839333.020623.png 1341839333.020647 depth/1341839333.020647.png
1341839333.056704 rgb/1341839333.056704.png 1341839333.056724 depth/1341839333.056724.png
1341839333.088657 rgb/1341839333.088657.png 1341839333.089114 depth/1341839333.089114.png
1341839333.120706 rgb/1341839333.120706.png 1341839333.120718 depth/1341839333.120718.png
1341839333.156633 rgb/1341839333.156633.png 1341839333.156704 depth/1341839333.156704.png
1341839333.188765 rgb/1341839333.188765.png 1341839333.188815 depth/1341839333.188815.png
1341839333.220616 rgb/1341839333.220616.png 1341839333.220628 depth/1341839333.220628.png
1341839333.256627 rgb/1341839333.256627.png 1341839333.256670 depth/1341839333.256670.png
1341839333.288720 rgb/1341839333.288720.png 1341839333.288740 depth/1341839333.288740.png
1341839333.320582 rgb/1341839333.320582.png 1341839333.320602 depth/1341839333.320602.png
1341839333.356732 rgb/1341839333.356732.png 1341839333.356748 depth/1341839333.356748.png
1341839333.388697 rgb/1341839333.388697.png 1341839333.388710 depth/1341839333.388710.png
1341839333.420710 rgb/1341839333.420710.png 1341839333.420733 depth/1341839333.420733.png
1341839333.456775 rgb/1341839333.456775.png 1341839333.456800 depth/1341839333.456800.png
1341839333.488704 rgb/1341839333.488704.png 1341839333.489161 depth/1341839333.489161.png
1341839333.524711 rgb/1341839333.524711.png 1341839333.524754 depth/1341839333.524754.png
1341839333.556624 rgb/1341839333.556624.png 1341839333.556641 depth/1341839333.556641.png
1341839333.588625 rgb/1341839333.588625.png 1341839333.588635 depth/1341839333.588635.png
1341839333.624629 rgb/1341839333.624629.png 1341839333.624660 depth/1341839333.624660.png
1341839333.656568 rgb/1341839333.656568.png 1341839333.656582 depth/1341839333.656582.png
1341839333.692659 rgb/1341839333.692659.png 1341839333.692674 depth/1341839333.692674.png
1341839333.724668 rgb/1341839333.724668.png 1341839333.724684 depth/1341839333.724684.png
1341839333.756687 rgb/1341839333.756687.png 1341839333.756705 depth/1341839333.756705.png
1341839333.792785 rgb/1341839333.792785.png 1341839333.792811 depth/1341839333.792811.png
1341839333.824592 rgb/1341839333.824592.png 1341839333.824607 depth/1341839333.824607.png
1341839333.860713 rgb/1341839333.860713.png 1341839333.860727 depth/1341839333.860727.png
1341839333.892664 rgb/1341839333.892664.png 1341839333.892675 depth/1341839333.892675.png
1341839333.924772 rgb/1341839333.924772.png 1341839333.924793 depth/1341839333.924793.png
1341839333.960800 rgb/1341839333.960800.png 1341839333.960816 depth/1341839333.960816.png
1341839333.992556 rgb/1341839333.992556.png 1341839333.992565 depth/1341839333.992565.png
1341839334.028677 rgb/1341839334.028677.png 1341839334.028692 depth/1341839334.028692.png
1341839334.060751 rgb/1341839334.060751.png 1341839334.061278 depth/1341839334.061278.png
1341839334.092709 rgb/1341839334.092709.png 1341839334.092728 depth/1341839334.092728.png
1341839334.128631 rgb/1341839334.128631.png 1341839334.128644 depth/1341839334.128644.png
1341839334.160667 rgb/1341839334.160667.png 1341839334.160704 depth/1341839334.160704.png
1341839334.196648 rgb/1341839334.196648.png 1341839334.197146 depth/1341839334.197146.png
1341839334.228784 rgb/1341839334.228784.png 1341839334.228803 depth/1341839334.228803.png
1341839334.260936 rgb/1341839334.260936.png 1341839334.260959 depth/1341839334.260959.png
1341839334.328751 rgb/1341839334.328751.png 1341839334.328809 depth/1341839334.328809.png
1341839334.389793 rgb/1341839334.389793.png 1341839334.389836 depth/1341839334.389836.png
1341839334.421707 rgb/1341839334.421707.png 1341839334.421774 depth/1341839334.421774.png
1341839334.458010 rgb/1341839334.458010.png 1341839334.458070 depth/1341839334.458070.png
1341839334.489685 rgb/1341839334.489685.png 1341839334.489716 depth/1341839334.489716.png
1341839334.525784 rgb/1341839334.525784.png 1341839334.525791 depth/1341839334.525791.png
1341839334.557792 rgb/1341839334.557792.png 1341839334.557800 depth/1341839334.557800.png
1341839334.589872 rgb/1341839334.589872.png 1341839334.589879 depth/1341839334.589879.png
1341839334.625782 rgb/1341839334.625782.png 1341839334.625795 depth/1341839334.625795.png
1341839334.657843 rgb/1341839334.657843.png 1341839334.657857 depth/1341839334.657857.png
1341839334.689637 rgb/1341839334.689637.png 1341839334.689650 depth/1341839334.689650.png
1341839334.725841 rgb/1341839334.725841.png 1341839334.725913 depth/1341839334.725913.png
1341839334.757940 rgb/1341839334.757940.png 1341839334.758001 depth/1341839334.758001.png
1341839334.793688 rgb/1341839334.793688.png 1341839334.794398 depth/1341839334.794398.png
1341839334.826159 rgb/1341839334.826159.png 1341839334.826176 depth/1341839334.826176.png
1341839334.857927 rgb/1341839334.857927.png 1341839334.858001 depth/1341839334.858001.png
1341839334.893837 rgb/1341839334.893837.png 1341839334.893846 depth/1341839334.893846.png
1341839334.925643 rgb/1341839334.925643.png 1341839334.925663 depth/1341839334.925663.png
1341839334.958884 rgb/1341839334.958884.png 1341839334.958897 depth/1341839334.958897.png
1341839334.993773 rgb/1341839334.993773.png 1341839334.993786 depth/1341839334.993786.png
1341839335.025708 rgb/1341839335.025708.png 1341839335.025736 depth/1341839335.025736.png
1341839335.061854 rgb/1341839335.061854.png 1341839335.062376 depth/1341839335.062376.png
1341839335.093687 rgb/1341839335.093687.png 1341839335.093705 depth/1341839335.093705.png
1341839335.125723 rgb/1341839335.125723.png 1341839335.125749 depth/1341839335.125749.png
1341839335.161765 rgb/1341839335.161765.png 1341839335.161801 depth/1341839335.161801.png
1341839335.193620 rgb/1341839335.193620.png 1341839335.193634 depth/1341839335.193634.png
1341839335.229620 rgb/1341839335.229620.png 1341839335.229637 depth/1341839335.229637.png
1341839335.261647 rgb/1341839335.261647.png 1341839335.261672 depth/1341839335.261672.png
1341839335.293594 rgb/1341839335.293594.png 1341839335.293601 depth/1341839335.293601.png
1341839335.330288 rgb/1341839335.330288.png 1341839335.330337 depth/1341839335.330337.png
1341839335.361768 rgb/1341839335.361768.png 1341839335.361795 depth/1341839335.361795.png
1341839335.393779 rgb/1341839335.393779.png 1341839335.393789 depth/1341839335.393789.png
1341839335.429685 rgb/1341839335.429685.png 1341839335.429852 depth/1341839335.429852.png
1341839335.461748 rgb/1341839335.461748.png 1341839335.461797 depth/1341839335.461797.png
1341839335.497763 rgb/1341839335.497763.png 1341839335.497824 depth/1341839335.497824.png
1341839335.529696 rgb/1341839335.529696.png 1341839335.529703 depth/1341839335.529703.png
1341839335.561678 rgb/1341839335.561678.png 1341839335.561688 depth/1341839335.561688.png
1341839335.597774 rgb/1341839335.597774.png 1341839335.597785 depth/1341839335.597785.png
1341839335.629668 rgb/1341839335.629668.png 1341839335.629720 depth/1341839335.629720.png
1341839335.661725 rgb/1341839335.661725.png 1341839335.661751 depth/1341839335.661751.png
1341839335.698267 rgb/1341839335.698267.png 1341839335.698291 depth/1341839335.698291.png
1341839335.729842 rgb/1341839335.729842.png 1341839335.729860 depth/1341839335.729860.png
1341839335.765671 rgb/1341839335.765671.png 1341839335.765694 depth/1341839335.765694.png
1341839335.798008 rgb/1341839335.798008.png 1341839335.798139 depth/1341839335.798139.png
1341839335.829597 rgb/1341839335.829597.png 1341839335.829611 depth/1341839335.829611.png
1341839335.865741 rgb/1341839335.865741.png 1341839335.865786 depth/1341839335.865786.png
1341839335.929801 rgb/1341839335.929801.png 1341839335.929832 depth/1341839335.929832.png
1341839335.965821 rgb/1341839335.965821.png 1341839335.965832 depth/1341839335.965832.png
1341839335.997645 rgb/1341839335.997645.png 1341839335.997676 depth/1341839335.997676.png
1341839336.033633 rgb/1341839336.033633.png 1341839336.033647 depth/1341839336.033647.png
1341839336.065708 rgb/1341839336.065708.png 1341839336.065734 depth/1341839336.065734.png
1341839336.097620 rgb/1341839336.097620.png 1341839336.097631 depth/1341839336.097631.png
1341839336.133580 rgb/1341839336.133580.png 1341839336.133597 depth/1341839336.133597.png
1341839336.165684 rgb/1341839336.165684.png 1341839336.165702 depth/1341839336.165702.png
1341839336.201770 rgb/1341839336.201770.png 1341839336.202267 depth/1341839336.202267.png
1341839336.234199 rgb/1341839336.234199.png 1341839336.234214 depth/1341839336.234214.png
1341839336.265733 rgb/1341839336.265733.png 1341839336.265756 depth/1341839336.265756.png
1341839336.301605 rgb/1341839336.301605.png 1341839336.301613 depth/1341839336.301613.png
1341839336.333617 rgb/1341839336.333617.png 1341839336.333632 depth/1341839336.333632.png
1341839336.365711 rgb/1341839336.365711.png 1341839336.365718 depth/1341839336.365718.png
1341839336.401651 rgb/1341839336.401651.png 1341839336.401664 depth/1341839336.401664.png
1341839336.433661 rgb/1341839336.433661.png 1341839336.433672 depth/1341839336.433672.png
1341839336.469753 rgb/1341839336.469753.png 1341839336.469794 depth/1341839336.469794.png
1341839336.501527 rgb/1341839336.501527.png 1341839336.501620 depth/1341839336.501620.png
1341839336.533643 rgb/1341839336.533643.png 1341839336.533664 depth/1341839336.533664.png
1341839336.569834 rgb/1341839336.569834.png 1341839336.569844 depth/1341839336.569844.png
1341839336.633720 rgb/1341839336.633720.png 1341839336.633742 depth/1341839336.633742.png
1341839336.669774 rgb/1341839336.669774.png 1341839336.669786 depth/1341839336.669786.png
1341839336.701623 rgb/1341839336.701623.png 1341839336.701630 depth/1341839336.701630.png
1341839336.737703 rgb/1341839336.737703.png 1341839336.737715 depth/1341839336.737715.png
1341839336.769713 rgb/1341839336.769713.png 1341839336.769724 depth/1341839336.769724.png
1341839336.801896 rgb/1341839336.801896.png 1341839336.801932 depth/1341839336.801932.png
1341839336.837710 rgb/1341839336.837710.png 1341839336.837725 depth/1341839336.837725.png
1341839336.869698 rgb/1341839336.869698.png 1341839336.869709 depth/1341839336.869709.png
1341839336.901648 rgb/1341839336.901648.png 1341839336.901683 depth/1341839336.901683.png
1341839336.937590 rgb/1341839336.937590.png 1341839336.937604 depth/1341839336.937604.png
1341839336.969791 rgb/1341839336.969791.png 1341839336.969803 depth/1341839336.969803.png
1341839337.005670 rgb/1341839337.005670.png 1341839337.005683 depth/1341839337.005683.png
1341839337.037737 rgb/1341839337.037737.png 1341839337.037752 depth/1341839337.037752.png
1341839337.069784 rgb/1341839337.069784.png 1341839337.069797 depth/1341839337.069797.png
1341839337.105703 rgb/1341839337.105703.png 1341839337.105718 depth/1341839337.105718.png
1341839337.137668 rgb/1341839337.137668.png 1341839337.137797 depth/1341839337.137797.png
1341839337.169654 rgb/1341839337.169654.png 1341839337.169667 depth/1341839337.169667.png
1341839337.205717 rgb/1341839337.205717.png 1341839337.205734 depth/1341839337.205734.png
1341839337.237736 rgb/1341839337.237736.png 1341839337.237749 depth/1341839337.237749.png
1341839337.273717 rgb/1341839337.273717.png 1341839337.273741 depth/1341839337.273741.png
1341839337.305689 rgb/1341839337.305689.png 1341839337.305704 depth/1341839337.305704.png
1341839337.337586 rgb/1341839337.337586.png 1341839337.337595 depth/1341839337.337595.png
1341839337.373728 rgb/1341839337.373728.png 1341839337.373961 depth/1341839337.373961.png
1341839337.405771 rgb/1341839337.405771.png 1341839337.405787 depth/1341839337.405787.png
1341839337.441982 rgb/1341839337.441982.png 1341839337.442004 depth/1341839337.442004.png
1341839337.473977 rgb/1341839337.473977.png 1341839337.474958 depth/1341839337.474958.png
1341839337.508609 rgb/1341839337.508609.png 1341839337.509733 depth/1341839337.509733.png
1341839337.543918 rgb/1341839337.543918.png 1341839337.544700 depth/1341839337.544700.png
1341839337.606146 rgb/1341839337.606146.png 1341839337.606582 depth/1341839337.606582.png
1341839337.641814 rgb/1341839337.641814.png 1341839337.643191 depth/1341839337.643191.png
1341839337.675262 rgb/1341839337.675262.png 1341839337.675557 depth/1341839337.675557.png
1341839337.709810 rgb/1341839337.709810.png 1341839337.709823 depth/1341839337.709823.png
1341839337.741912 rgb/1341839337.741912.png 1341839337.741931 depth/1341839337.741931.png
1341839337.774188 rgb/1341839337.774188.png 1341839337.775641 depth/1341839337.775641.png
1341839337.809638 rgb/1341839337.809638.png 1341839337.809663 depth/1341839337.809663.png
1341839337.841586 rgb/1341839337.841586.png 1341839337.841607 depth/1341839337.841607.png
1341839337.873743 rgb/1341839337.873743.png 1341839337.873966 depth/1341839337.873966.png
1341839337.909675 rgb/1341839337.909675.png 1341839337.909686 depth/1341839337.909686.png
1341839337.941639 rgb/1341839337.941639.png 1341839337.941649 depth/1341839337.941649.png
1341839337.977798 rgb/1341839337.977798.png 1341839337.978034 depth/1341839337.978034.png
1341839338.010031 rgb/1341839338.010031.png 1341839338.010055 depth/1341839338.010055.png
1341839338.041702 rgb/1341839338.041702.png 1341839338.041796 depth/1341839338.041796.png
1341839338.077694 rgb/1341839338.077694.png 1341839338.077718 depth/1341839338.077718.png
1341839338.109774 rgb/1341839338.109774.png 1341839338.109796 depth/1341839338.109796.png
1341839338.141722 rgb/1341839338.141722.png 1341839338.141788 depth/1341839338.141788.png
1341839338.177697 rgb/1341839338.177697.png 1341839338.177722 depth/1341839338.177722.png
1341839338.209836 rgb/1341839338.209836.png 1341839338.209855 depth/1341839338.209855.png
1341839338.245657 rgb/1341839338.245657.png 1341839338.245667 depth/1341839338.245667.png
1341839338.277654 rgb/1341839338.277654.png 1341839338.277664 depth/1341839338.277664.png
1341839338.309709 rgb/1341839338.309709.png 1341839338.310236 depth/1341839338.310236.png
1341839338.346052 rgb/1341839338.346052.png 1341839338.346061 depth/1341839338.346061.png
1341839338.377746 rgb/1341839338.377746.png 1341839338.377771 depth/1341839338.377771.png
1341839338.414018 rgb/1341839338.414018.png 1341839338.414172 depth/1341839338.414172.png
1341839338.445575 rgb/1341839338.445575.png 1341839338.445621 depth/1341839338.445621.png
1341839338.477556 rgb/1341839338.477556.png 1341839338.477593 depth/1341839338.477593.png
1341839338.513581 rgb/1341839338.513581.png 1341839338.513631 depth/1341839338.513631.png
1341839338.545689 rgb/1341839338.545689.png 1341839338.545729 depth/1341839338.545729.png
1341839338.578283 rgb/1341839338.578283.png 1341839338.578307 depth/1341839338.578307.png
1341839338.613599 rgb/1341839338.613599.png 1341839338.613629 depth/1341839338.613629.png
1341839338.645675 rgb/1341839338.645675.png 1341839338.645705 depth/1341839338.645705.png
1341839338.681727 rgb/1341839338.681727.png 1341839338.681745 depth/1341839338.681745.png
1341839338.713893 rgb/1341839338.713893.png 1341839338.713936 depth/1341839338.713936.png
1341839338.781709 rgb/1341839338.781709.png 1341839338.781731 depth/1341839338.781731.png
1341839338.813730 rgb/1341839338.813730.png 1341839338.813789 depth/1341839338.813789.png
1341839338.845877 rgb/1341839338.845877.png 1341839338.845925 depth/1341839338.845925.png
1341839338.881802 rgb/1341839338.881802.png 1341839338.881852 depth/1341839338.881852.png
1341839338.913653 rgb/1341839338.913653.png 1341839338.913691 depth/1341839338.913691.png
1341839338.949676 rgb/1341839338.949676.png 1341839338.950055 depth/1341839338.950055.png
1341839338.981956 rgb/1341839338.981956.png 1341839338.982022 depth/1341839338.982022.png
1341839339.013697 rgb/1341839339.013697.png 1341839339.013706 depth/1341839339.013706.png
1341839339.049615 rgb/1341839339.049615.png 1341839339.049635 depth/1341839339.049635.png
1341839339.081735 rgb/1341839339.081735.png 1341839339.081747 depth/1341839339.081747.png
1341839339.113711 rgb/1341839339.113711.png 1341839339.113723 depth/1341839339.113723.png
1341839339.149680 rgb/1341839339.149680.png 1341839339.149743 depth/1341839339.149743.png
1341839339.181651 rgb/1341839339.181651.png 1341839339.181663 depth/1341839339.181663.png
1341839339.217865 rgb/1341839339.217865.png 1341839339.217881 depth/1341839339.217881.png
1341839339.249837 rgb/1341839339.249837.png 1341839339.249852 depth/1341839339.249852.png
1341839339.281657 rgb/1341839339.281657.png 1341839339.281688 depth/1341839339.281688.png
1341839339.317672 rgb/1341839339.317672.png 1341839339.317698 depth/1341839339.317698.png
1341839339.349560 rgb/1341839339.349560.png 1341839339.349572 depth/1341839339.349572.png
1341839339.381716 rgb/1341839339.381716.png 1341839339.381744 depth/1341839339.381744.png
1341839339.417573 rgb/1341839339.417573.png 1341839339.417594 depth/1341839339.417594.png
1341839339.449681 rgb/1341839339.449681.png 1341839339.449770 depth/1341839339.449770.png
1341839339.485695 rgb/1341839339.485695.png 1341839339.485862 depth/1341839339.485862.png
1341839339.517711 rgb/1341839339.517711.png 1341839339.517723 depth/1341839339.517723.png
1341839339.549709 rgb/1341839339.549709.png 1341839339.549722 depth/1341839339.549722.png
1341839339.585694 rgb/1341839339.585694.png 1341839339.585708 depth/1341839339.585708.png
1341839339.617734 rgb/1341839339.617734.png 1341839339.617755 depth/1341839339.617755.png
1341839339.653664 rgb/1341839339.653664.png 1341839339.653686 depth/1341839339.653686.png
1341839339.685594 rgb/1341839339.685594.png 1341839339.685607 depth/1341839339.685607.png
1341839339.725102 rgb/1341839339.725102.png 1341839339.717688 depth/1341839339.717688.png
1341839339.785820 rgb/1341839339.785820.png 1341839339.785841 depth/1341839339.785841.png
1341839339.817649 rgb/1341839339.817649.png 1341839339.817673 depth/1341839339.817673.png
1341839339.853678 rgb/1341839339.853678.png 1341839339.853689 depth/1341839339.853689.png
1341839339.885719 rgb/1341839339.885719.png 1341839339.886194 depth/1341839339.886194.png
1341839339.921797 rgb/1341839339.921797.png 1341839339.921810 depth/1341839339.921810.png
1341839339.953700 rgb/1341839339.953700.png 1341839339.953712 depth/1341839339.953712.png
1341839339.985622 rgb/1341839339.985622.png 1341839339.985940 depth/1341839339.985940.png
1341839340.021864 rgb/1341839340.021864.png 1341839340.021944 depth/1341839340.021944.png
1341839340.053574 rgb/1341839340.053574.png 1341839340.053625 depth/1341839340.053625.png
1341839340.085831 rgb/1341839340.085831.png 1341839340.085849 depth/1341839340.085849.png
1341839340.121782 rgb/1341839340.121782.png 1341839340.121790 depth/1341839340.121790.png
1341839340.153668 rgb/1341839340.153668.png 1341839340.153725 depth/1341839340.153725.png
1341839340.189753 rgb/1341839340.189753.png 1341839340.189767 depth/1341839340.189767.png
1341839340.221730 rgb/1341839340.221730.png 1341839340.221740 depth/1341839340.221740.png
1341839340.253773 rgb/1341839340.253773.png 1341839340.253797 depth/1341839340.253797.png
1341839340.289866 rgb/1341839340.289866.png 1341839340.289889 depth/1341839340.289889.png
1341839340.321580 rgb/1341839340.321580.png 1341839340.321596 depth/1341839340.321596.png
1341839340.353715 rgb/1341839340.353715.png 1341839340.353760 depth/1341839340.353760.png
1341839340.389755 rgb/1341839340.389755.png 1341839340.390182 depth/1341839340.390182.png
1341839340.422038 rgb/1341839340.422038.png 1341839340.422046 depth/1341839340.422046.png
1341839340.457698 rgb/1341839340.457698.png 1341839340.457730 depth/1341839340.457730.png
1341839340.489727 rgb/1341839340.489727.png 1341839340.489763 depth/1341839340.489763.png
1341839340.521632 rgb/1341839340.521632.png 1341839340.521641 depth/1341839340.521641.png
1341839340.557783 rgb/1341839340.557783.png 1341839340.557814 depth/1341839340.557814.png
1341839340.589579 rgb/1341839340.589579.png 1341839340.589605 depth/1341839340.589605.png
1341839340.625761 rgb/1341839340.625761.png 1341839340.625790 depth/1341839340.625790.png
1341839340.657658 rgb/1341839340.657658.png 1341839340.657932 depth/1341839340.657932.png
1341839340.689692 rgb/1341839340.689692.png 1341839340.689715 depth/1341839340.689715.png
1341839340.725740 rgb/1341839340.725740.png 1341839340.725751 depth/1341839340.725751.png
1341839340.757924 rgb/1341839340.757924.png 1341839340.757955 depth/1341839340.757955.png
1341839340.789679 rgb/1341839340.789679.png 1341839340.789691 depth/1341839340.789691.png
1341839340.825682 rgb/1341839340.825682.png 1341839340.825704 depth/1341839340.825704.png
1341839340.857588 rgb/1341839340.857588.png 1341839340.857619 depth/1341839340.857619.png
1341839340.893730 rgb/1341839340.893730.png 1341839340.893741 depth/1341839340.893741.png
1341839340.925735 rgb/1341839340.925735.png 1341839340.925744 depth/1341839340.925744.png
1341839340.957629 rgb/1341839340.957629.png 1341839340.957673 depth/1341839340.957673.png
1341839340.993772 rgb/1341839340.993772.png 1341839340.993781 depth/1341839340.993781.png
1341839341.025671 rgb/1341839341.025671.png 1341839341.025719 depth/1341839341.025719.png
1341839341.057806 rgb/1341839341.057806.png 1341839341.057817 depth/1341839341.057817.png
1341839341.093662 rgb/1341839341.093662.png 1341839341.093674 depth/1341839341.093674.png
1341839341.125745 rgb/1341839341.125745.png 1341839341.125757 depth/1341839341.125757.png
1341839341.161589 rgb/1341839341.161589.png 1341839341.161613 depth/1341839341.161613.png
1341839341.193897 rgb/1341839341.193897.png 1341839341.193914 depth/1341839341.193914.png
1341839341.261788 rgb/1341839341.261788.png 1341839341.261807 depth/1341839341.261807.png
1341839341.293674 rgb/1341839341.293674.png 1341839341.294203 depth/1341839341.294203.png
1341839341.325653 rgb/1341839341.325653.png 1341839341.325664 depth/1341839341.325664.png
1341839341.361673 rgb/1341839341.361673.png 1341839341.361807 depth/1341839341.361807.png
1341839341.393787 rgb/1341839341.393787.png 1341839341.394547 depth/1341839341.394547.png
1341839341.429785 rgb/1341839341.429785.png 1341839341.429797 depth/1341839341.429797.png
1341839341.461594 rgb/1341839341.461594.png 1341839341.461658 depth/1341839341.461658.png
1341839341.493666 rgb/1341839341.493666.png 1341839341.494148 depth/1341839341.494148.png
1341839341.529752 rgb/1341839341.529752.png 1341839341.529786 depth/1341839341.529786.png
1341839341.561764 rgb/1341839341.561764.png 1341839341.561773 depth/1341839341.561773.png
1341839341.593691 rgb/1341839341.593691.png 1341839341.593704 depth/1341839341.593704.png
1341839341.629657 rgb/1341839341.629657.png 1341839341.629668 depth/1341839341.629668.png
1341839341.662189 rgb/1341839341.662189.png 1341839341.662204 depth/1341839341.662204.png
1341839341.697693 rgb/1341839341.697693.png 1341839341.697707 depth/1341839341.697707.png
1341839341.729716 rgb/1341839341.729716.png 1341839341.729730 depth/1341839341.729730.png
1341839341.761680 rgb/1341839341.761680.png 1341839341.761718 depth/1341839341.761718.png
1341839341.797656 rgb/1341839341.797656.png 1341839341.797672 depth/1341839341.797672.png
1341839341.829696 rgb/1341839341.829696.png 1341839341.829711 depth/1341839341.829711.png
1341839341.865686 rgb/1341839341.865686.png 1341839341.865698 depth/1341839341.865698.png
1341839341.897659 rgb/1341839341.897659.png 1341839341.897671 depth/1341839341.897671.png
1341839341.929651 rgb/1341839341.929651.png 1341839341.929668 depth/1341839341.929668.png
1341839341.966152 rgb/1341839341.966152.png 1341839341.966161 depth/1341839341.966161.png
1341839341.997665 rgb/1341839341.997665.png 1341839341.997822 depth/1341839341.997822.png
1341839342.029793 rgb/1341839342.029793.png 1341839342.029821 depth/1341839342.029821.png
1341839342.065765 rgb/1341839342.065765.png 1341839342.065778 depth/1341839342.065778.png
1341839342.097737 rgb/1341839342.097737.png 1341839342.097747 depth/1341839342.097747.png
1341839342.133572 rgb/1341839342.133572.png 1341839342.133584 depth/1341839342.133584.png
1341839342.165740 rgb/1341839342.165740.png 1341839342.165747 depth/1341839342.165747.png
1341839342.197680 rgb/1341839342.197680.png 1341839342.197690 depth/1341839342.197690.png
1341839342.233630 rgb/1341839342.233630.png 1341839342.233646 depth/1341839342.233646.png
1341839342.265857 rgb/1341839342.265857.png 1341839342.265874 depth/1341839342.265874.png
1341839342.297900 rgb/1341839342.297900.png 1341839342.297925 depth/1341839342.297925.png
1341839342.334490 rgb/1341839342.334490.png 1341839342.335634 depth/1341839342.335634.png
1341839342.366742 rgb/1341839342.366742.png 1341839342.367875 depth/1341839342.367875.png
1341839342.401681 rgb/1341839342.401681.png 1341839342.401982 depth/1341839342.401982.png
1341839342.433833 rgb/1341839342.433833.png 1341839342.433927 depth/1341839342.433927.png
1341839342.465726 rgb/1341839342.465726.png 1341839342.465742 depth/1341839342.465742.png
1341839342.501647 rgb/1341839342.501647.png 1341839342.501672 depth/1341839342.501672.png
1341839342.540751 rgb/1341839342.540751.png 1341839342.540774 depth/1341839342.540774.png
1341839342.601758 rgb/1341839342.601758.png 1341839342.601781 depth/1341839342.601781.png
1341839342.669819 rgb/1341839342.669819.png 1341839342.669836 depth/1341839342.669836.png
1341839342.701951 rgb/1341839342.701951.png 1341839342.701958 depth/1341839342.701958.png
1341839342.733628 rgb/1341839342.733628.png 1341839342.734327 depth/1341839342.734327.png
1341839342.769533 rgb/1341839342.769533.png 1341839342.769575 depth/1341839342.769575.png
1341839342.801681 rgb/1341839342.801681.png 1341839342.801697 depth/1341839342.801697.png
1341839342.837574 rgb/1341839342.837574.png 1341839342.837599 depth/1341839342.837599.png
1341839342.869635 rgb/1341839342.869635.png 1341839342.869657 depth/1341839342.869657.png
1341839342.901615 rgb/1341839342.901615.png 1341839342.901629 depth/1341839342.901629.png
1341839342.937722 rgb/1341839342.937722.png 1341839342.937752 depth/1341839342.937752.png
1341839342.969783 rgb/1341839342.969783.png 1341839342.969809 depth/1341839342.969809.png
1341839343.001730 rgb/1341839343.001730.png 1341839343.001757 depth/1341839343.001757.png
1341839343.037568 rgb/1341839343.037568.png 1341839343.037598 depth/1341839343.037598.png
1341839343.069751 rgb/1341839343.069751.png 1341839343.069778 depth/1341839343.069778.png
1341839343.105654 rgb/1341839343.105654.png 1341839343.105680 depth/1341839343.105680.png
1341839343.137584 rgb/1341839343.137584.png 1341839343.137599 depth/1341839343.137599.png
1341839343.169670 rgb/1341839343.169670.png 1341839343.169689 depth/1341839343.169689.png
1341839343.205656 rgb/1341839343.205656.png 1341839343.205678 depth/1341839343.205678.png
1341839343.237612 rgb/1341839343.237612.png 1341839343.237627 depth/1341839343.237627.png
1341839343.305779 rgb/1341839343.305779.png 1341839343.305796 depth/1341839343.305796.png
1341839343.337587 rgb/1341839343.337587.png 1341839343.337603 depth/1341839343.337603.png
1341839343.373793 rgb/1341839343.373793.png 1341839343.373816 depth/1341839343.373816.png
1341839343.405587 rgb/1341839343.405587.png 1341839343.405615 depth/1341839343.405615.png
1341839343.437639 rgb/1341839343.437639.png 1341839343.437656 depth/1341839343.437656.png
1341839343.473895 rgb/1341839343.473895.png 1341839343.473926 depth/1341839343.473926.png
1341839343.505595 rgb/1341839343.505595.png 1341839343.505604 depth/1341839343.505604.png
1341839343.537619 rgb/1341839343.537619.png 1341839343.537630 depth/1341839343.537630.png
1341839343.573926 rgb/1341839343.573926.png 1341839343.573940 depth/1341839343.573940.png
1341839343.605784 rgb/1341839343.605784.png 1341839343.605808 depth/1341839343.605808.png
1341839343.641726 rgb/1341839343.641726.png 1341839343.641734 depth/1341839343.641734.png
1341839343.673994 rgb/1341839343.673994.png 1341839343.674008 depth/1341839343.674008.png
1341839343.705911 rgb/1341839343.705911.png 1341839343.706617 depth/1341839343.706617.png
1341839343.741614 rgb/1341839343.741614.png 1341839343.741621 depth/1341839343.741621.png
1341839343.774055 rgb/1341839343.774055.png 1341839343.774086 depth/1341839343.774086.png
1341839343.805691 rgb/1341839343.805691.png 1341839343.805716 depth/1341839343.805716.png
1341839343.841823 rgb/1341839343.841823.png 1341839343.841908 depth/1341839343.841908.png
1341839343.873716 rgb/1341839343.873716.png 1341839343.873728 depth/1341839343.873728.png
1341839343.909636 rgb/1341839343.909636.png 1341839343.909667 depth/1341839343.909667.png
1341839343.941606 rgb/1341839343.941606.png 1341839343.941616 depth/1341839343.941616.png
1341839343.973942 rgb/1341839343.973942.png 1341839343.973980 depth/1341839343.973980.png
1341839344.009670 rgb/1341839344.009670.png 1341839344.009680 depth/1341839344.009680.png
1341839344.041779 rgb/1341839344.041779.png 1341839344.041837 depth/1341839344.041837.png
1341839344.077608 rgb/1341839344.077608.png 1341839344.077657 depth/1341839344.077657.png
1341839344.109759 rgb/1341839344.109759.png 1341839344.109836 depth/1341839344.109836.png
1341839344.141693 rgb/1341839344.141693.png 1341839344.141705 depth/1341839344.141705.png
1341839344.177686 rgb/1341839344.177686.png 1341839344.177702 depth/1341839344.177702.png
1341839344.209677 rgb/1341839344.209677.png 1341839344.209717 depth/1341839344.209717.png
1341839344.241575 rgb/1341839344.241575.png 1341839344.241645 depth/1341839344.241645.png
1341839344.277638 rgb/1341839344.277638.png 1341839344.277671 depth/1341839344.277671.png
1341839344.309629 rgb/1341839344.309629.png 1341839344.309705 depth/1341839344.309705.png
1341839344.345784 rgb/1341839344.345784.png 1341839344.345801 depth/1341839344.345801.png
1341839344.377695 rgb/1341839344.377695.png 1341839344.377710 depth/1341839344.377710.png
1341839344.409722 rgb/1341839344.409722.png 1341839344.409739 depth/1341839344.409739.png
1341839344.445749 rgb/1341839344.445749.png 1341839344.445778 depth/1341839344.445778.png
1341839344.477598 rgb/1341839344.477598.png 1341839344.477610 depth/1341839344.477610.png
1341839344.510290 rgb/1341839344.510290.png 1341839344.510307 depth/1341839344.510307.png
1341839344.545735 rgb/1341839344.545735.png 1341839344.545748 depth/1341839344.545748.png
1341839344.577829 rgb/1341839344.577829.png 1341839344.577848 depth/1341839344.577848.png
1341839344.613708 rgb/1341839344.613708.png 1341839344.613724 depth/1341839344.613724.png
1341839344.645705 rgb/1341839344.645705.png 1341839344.645720 depth/1341839344.645720.png
1341839344.677613 rgb/1341839344.677613.png 1341839344.677623 depth/1341839344.677623.png
1341839344.713772 rgb/1341839344.713772.png 1341839344.713889 depth/1341839344.713889.png
1341839344.746130 rgb/1341839344.746130.png 1341839344.746136 depth/1341839344.746136.png
1341839344.777798 rgb/1341839344.777798.png 1341839344.777806 depth/1341839344.777806.png
1341839344.813709 rgb/1341839344.813709.png 1341839344.813721 depth/1341839344.813721.png
1341839344.845871 rgb/1341839344.845871.png 1341839344.845917 depth/1341839344.845917.png
1341839344.881699 rgb/1341839344.881699.png 1341839344.881716 depth/1341839344.881716.png
1341839344.914032 rgb/1341839344.914032.png 1341839344.914064 depth/1341839344.914064.png
1341839344.981832 rgb/1341839344.981832.png 1341839344.981867 depth/1341839344.981867.png
1341839345.049749 rgb/1341839345.049749.png 1341839345.049773 depth/1341839345.049773.png
1341839345.081699 rgb/1341839345.081699.png 1341839345.081754 depth/1341839345.081754.png
1341839345.113768 rgb/1341839345.113768.png 1341839345.113787 depth/1341839345.113787.png
1341839345.149757 rgb/1341839345.149757.png 1341839345.149765 depth/1341839345.149765.png
1341839345.181590 rgb/1341839345.181590.png 1341839345.181679 depth/1341839345.181679.png
1341839345.213863 rgb/1341839345.213863.png 1341839345.213887 depth/1341839345.213887.png
1341839345.249611 rgb/1341839345.249611.png 1341839345.249641 depth/1341839345.249641.png
1341839345.281827 rgb/1341839345.281827.png 1341839345.281851 depth/1341839345.281851.png
1341839345.317669 rgb/1341839345.317669.png 1341839345.318190 depth/1341839345.318190.png
1341839345.381810 rgb/1341839345.381810.png 1341839345.381825 depth/1341839345.381825.png
1341839345.417639 rgb/1341839345.417639.png 1341839345.417661 depth/1341839345.417661.png
1341839345.449697 rgb/1341839345.449697.png 1341839345.449712 depth/1341839345.449712.png
1341839345.484384 rgb/1341839345.484384.png 1341839345.484398 depth/1341839345.484398.png
1341839345.517977 rgb/1341839345.517977.png 1341839345.517996 depth/1341839345.517996.png
1341839345.550478 rgb/1341839345.550478.png 1341839345.550489 depth/1341839345.550489.png
1341839345.585698 rgb/1341839345.585698.png 1341839345.585734 depth/1341839345.585734.png
1341839345.620249 rgb/1341839345.620249.png 1341839345.620844 depth/1341839345.620844.png
1341839345.656836 rgb/1341839345.656836.png 1341839345.656909 depth/1341839345.656909.png
1341839345.688614 rgb/1341839345.688614.png 1341839345.688622 depth/1341839345.688622.png
1341839345.720655 rgb/1341839345.720655.png 1341839345.720671 depth/1341839345.720671.png
1341839345.756797 rgb/1341839345.756797.png 1341839345.756838 depth/1341839345.756838.png
1341839345.788610 rgb/1341839345.788610.png 1341839345.788625 depth/1341839345.788625.png
1341839345.824841 rgb/1341839345.824841.png 1341839345.824857 depth/1341839345.824857.png
1341839345.857443 rgb/1341839345.857443.png 1341839345.857455 depth/1341839345.857455.png
1341839345.888695 rgb/1341839345.888695.png 1341839345.888708 depth/1341839345.888708.png
1341839345.924817 rgb/1341839345.924817.png 1341839345.924863 depth/1341839345.924863.png
1341839345.956605 rgb/1341839345.956605.png 1341839345.957143 depth/1341839345.957143.png
1341839345.992629 rgb/1341839345.992629.png 1341839345.993158 depth/1341839345.993158.png
1341839346.024783 rgb/1341839346.024783.png 1341839346.024797 depth/1341839346.024797.png
1341839346.060648 rgb/1341839346.060648.png 1341839346.060663 depth/1341839346.060663.png
1341839346.093032 rgb/1341839346.093032.png 1341839346.093046 depth/1341839346.093046.png
1341839346.124985 rgb/1341839346.124985.png 1341839346.125006 depth/1341839346.125006.png
1341839346.160766 rgb/1341839346.160766.png 1341839346.161318 depth/1341839346.161318.png
1341839346.192680 rgb/1341839346.192680.png 1341839346.192773 depth/1341839346.192773.png
1341839346.228607 rgb/1341839346.228607.png 1341839346.228629 depth/1341839346.228629.png
1341839346.289914 rgb/1341839346.289914.png 1341839346.289939 depth/1341839346.289939.png
1341839346.329287 rgb/1341839346.329287.png 1341839346.329312 depth/1341839346.329312.png
1341839346.360711 rgb/1341839346.360711.png 1341839346.360723 depth/1341839346.360723.png
1341839346.396649 rgb/1341839346.396649.png 1341839346.396661 depth/1341839346.396661.png
1341839346.428652 rgb/1341839346.428652.png 1341839346.428667 depth/1341839346.428667.png
1341839346.460699 rgb/1341839346.460699.png 1341839346.460712 depth/1341839346.460712.png
1341839346.496697 rgb/1341839346.496697.png 1341839346.496730 depth/1341839346.496730.png
1341839346.528703 rgb/1341839346.528703.png 1341839346.529245 depth/1341839346.529245.png
1341839346.564637 rgb/1341839346.564637.png 1341839346.564647 depth/1341839346.564647.png
1341839346.596825 rgb/1341839346.596825.png 1341839346.596836 depth/1341839346.596836.png
1341839346.628694 rgb/1341839346.628694.png 1341839346.629205 depth/1341839346.629205.png
1341839346.664637 rgb/1341839346.664637.png 1341839346.664666 depth/1341839346.664666.png
1341839346.696886 rgb/1341839346.696886.png 1341839346.697459 depth/1341839346.697459.png
1341839346.728718 rgb/1341839346.728718.png 1341839346.728784 depth/1341839346.728784.png
1341839346.764595 rgb/1341839346.764595.png 1341839346.764614 depth/1341839346.764614.png
1341839346.796696 rgb/1341839346.796696.png 1341839346.796721 depth/1341839346.796721.png
1341839346.832738 rgb/1341839346.832738.png 1341839346.832754 depth/1341839346.832754.png
1341839346.864859 rgb/1341839346.864859.png 1341839346.864887 depth/1341839346.864887.png
1341839346.896717 rgb/1341839346.896717.png 1341839346.896738 depth/1341839346.896738.png
1341839346.932707 rgb/1341839346.932707.png 1341839346.932720 depth/1341839346.932720.png
1341839346.964729 rgb/1341839346.964729.png 1341839346.964747 depth/1341839346.964747.png
1341839346.996794 rgb/1341839346.996794.png 1341839346.997094 depth/1341839346.997094.png
1341839347.032667 rgb/1341839347.032667.png 1341839347.032687 depth/1341839347.032687.png
1341839347.064794 rgb/1341839347.064794.png 1341839347.064803 depth/1341839347.064803.png
1341839347.096852 rgb/1341839347.096852.png 1341839347.096949 depth/1341839347.096949.png
1341839347.132647 rgb/1341839347.132647.png 1341839347.132674 depth/1341839347.132674.png
1341839347.164773 rgb/1341839347.164773.png 1341839347.164815 depth/1341839347.164815.png
1341839347.200676 rgb/1341839347.200676.png 1341839347.201086 depth/1341839347.201086.png
1341839347.232838 rgb/1341839347.232838.png 1341839347.232888 depth/1341839347.232888.png
1341839347.264666 rgb/1341839347.264666.png 1341839347.264678 depth/1341839347.264678.png
1341839347.300747 rgb/1341839347.300747.png 1341839347.300769 depth/1341839347.300769.png
1341839347.332783 rgb/1341839347.332783.png 1341839347.332810 depth/1341839347.332810.png
1341839347.364685 rgb/1341839347.364685.png 1341839347.364696 depth/1341839347.364696.png
1341839347.400746 rgb/1341839347.400746.png 1341839347.400758 depth/1341839347.400758.png
1341839347.432739 rgb/1341839347.432739.png 1341839347.432768 depth/1341839347.432768.png
1341839347.464647 rgb/1341839347.464647.png 1341839347.464678 depth/1341839347.464678.png
1341839347.500724 rgb/1341839347.500724.png 1341839347.500741 depth/1341839347.500741.png
1341839347.532880 rgb/1341839347.532880.png 1341839347.532902 depth/1341839347.532902.png
1341839347.564698 rgb/1341839347.564698.png 1341839347.564722 depth/1341839347.564722.png
1341839347.600778 rgb/1341839347.600778.png 1341839347.600810 depth/1341839347.600810.png
1341839347.632793 rgb/1341839347.632793.png 1341839347.632816 depth/1341839347.632816.png
1341839347.668741 rgb/1341839347.668741.png 1341839347.668756 depth/1341839347.668756.png
1341839347.700627 rgb/1341839347.700627.png 1341839347.700646 depth/1341839347.700646.png
1341839347.732741 rgb/1341839347.732741.png 1341839347.732763 depth/1341839347.732763.png
1341839347.768676 rgb/1341839347.768676.png 1341839347.768688 depth/1341839347.768688.png
1341839347.800791 rgb/1341839347.800791.png 1341839347.800813 depth/1341839347.800813.png
1341839347.868672 rgb/1341839347.868672.png 1341839347.868719 depth/1341839347.868719.png
1341839347.929775 rgb/1341839347.929775.png 1341839347.929819 depth/1341839347.929819.png
1341839347.961833 rgb/1341839347.961833.png 1341839347.961854 depth/1341839347.961854.png
1341839347.997737 rgb/1341839347.997737.png 1341839347.997747 depth/1341839347.997747.png
1341839348.030155 rgb/1341839348.030155.png 1341839348.030199 depth/1341839348.030199.png
1341839348.065703 rgb/1341839348.065703.png 1341839348.065716 depth/1341839348.065716.png
1341839348.097826 rgb/1341839348.097826.png 1341839348.097839 depth/1341839348.097839.png
1341839348.129675 rgb/1341839348.129675.png 1341839348.129730 depth/1341839348.129730.png
1341839348.168640 rgb/1341839348.168640.png 1341839348.168751 depth/1341839348.168751.png
1341839348.229823 rgb/1341839348.229823.png 1341839348.229846 depth/1341839348.229846.png
1341839348.265775 rgb/1341839348.265775.png 1341839348.265808 depth/1341839348.265808.png
1341839348.297754 rgb/1341839348.297754.png 1341839348.297768 depth/1341839348.297768.png
1341839348.333717 rgb/1341839348.333717.png 1341839348.333745 depth/1341839348.333745.png
1341839348.365676 rgb/1341839348.365676.png 1341839348.365708 depth/1341839348.365708.png
1341839348.398212 rgb/1341839348.398212.png 1341839348.398979 depth/1341839348.398979.png
1341839348.433965 rgb/1341839348.433965.png 1341839348.433976 depth/1341839348.433976.png
1341839348.465810 rgb/1341839348.465810.png 1341839348.467049 depth/1341839348.467049.png
1341839348.502540 rgb/1341839348.502540.png 1341839348.502595 depth/1341839348.502595.png
1341839348.535817 rgb/1341839348.535817.png 1341839348.535836 depth/1341839348.535836.png
1341839348.571279 rgb/1341839348.571279.png 1341839348.572285 depth/1341839348.572285.png
1341839348.602658 rgb/1341839348.602658.png 1341839348.603842 depth/1341839348.603842.png
1341839348.669100 rgb/1341839348.669100.png 1341839348.670608 depth/1341839348.670608.png
1341839348.733880 rgb/1341839348.733880.png 1341839348.733895 depth/1341839348.733895.png
1341839348.769820 rgb/1341839348.769820.png 1341839348.769839 depth/1341839348.769839.png
1341839348.801702 rgb/1341839348.801702.png 1341839348.801715 depth/1341839348.801715.png
1341839348.833872 rgb/1341839348.833872.png 1341839348.833968 depth/1341839348.833968.png
1341839348.869688 rgb/1341839348.869688.png 1341839348.869700 depth/1341839348.869700.png
1341839348.901723 rgb/1341839348.901723.png 1341839348.901741 depth/1341839348.901741.png
1341839348.933633 rgb/1341839348.933633.png 1341839348.933668 depth/1341839348.933668.png
1341839348.969728 rgb/1341839348.969728.png 1341839348.969744 depth/1341839348.969744.png
1341839349.001667 rgb/1341839349.001667.png 1341839349.001702 depth/1341839349.001702.png
1341839349.037748 rgb/1341839349.037748.png 1341839349.037768 depth/1341839349.037768.png
1341839349.069682 rgb/1341839349.069682.png 1341839349.069693 depth/1341839349.069693.png
1341839349.101803 rgb/1341839349.101803.png 1341839349.101825 depth/1341839349.101825.png
1341839349.137732 rgb/1341839349.137732.png 1341839349.137754 depth/1341839349.137754.png
1341839349.169619 rgb/1341839349.169619.png 1341839349.169628 depth/1341839349.169628.png
1341839349.201697 rgb/1341839349.201697.png 1341839349.201708 depth/1341839349.201708.png
1341839349.237802 rgb/1341839349.237802.png 1341839349.237814 depth/1341839349.237814.png
1341839349.269840 rgb/1341839349.269840.png 1341839349.269853 depth/1341839349.269853.png
1341839349.305885 rgb/1341839349.305885.png 1341839349.305943 depth/1341839349.305943.png
1341839349.338036 rgb/1341839349.338036.png 1341839349.339088 depth/1341839349.339088.png
1341839349.369771 rgb/1341839349.369771.png 1341839349.369787 depth/1341839349.369787.png
1341839349.405706 rgb/1341839349.405706.png 1341839349.405720 depth/1341839349.405720.png
1341839349.437665 rgb/1341839349.437665.png 1341839349.437724 depth/1341839349.437724.png
1341839349.473716 rgb/1341839349.473716.png 1341839349.473729 depth/1341839349.473729.png
1341839349.505708 rgb/1341839349.505708.png 1341839349.505725 depth/1341839349.505725.png
1341839349.537635 rgb/1341839349.537635.png 1341839349.537652 depth/1341839349.537652.png
1341839349.573786 rgb/1341839349.573786.png 1341839349.573799 depth/1341839349.573799.png
1341839349.605579 rgb/1341839349.605579.png 1341839349.605590 depth/1341839349.605590.png
1341839349.637702 rgb/1341839349.637702.png 1341839349.637724 depth/1341839349.637724.png
1341839349.673713 rgb/1341839349.673713.png 1341839349.673741 depth/1341839349.673741.png
1341839349.705908 rgb/1341839349.705908.png 1341839349.705934 depth/1341839349.705934.png
1341839349.741751 rgb/1341839349.741751.png 1341839349.741765 depth/1341839349.741765.png
1341839349.773786 rgb/1341839349.773786.png 1341839349.773825 depth/1341839349.773825.png
1341839349.805812 rgb/1341839349.805812.png 1341839349.805826 depth/1341839349.805826.png
1341839349.841758 rgb/1341839349.841758.png 1341839349.841772 depth/1341839349.841772.png
1341839349.873668 rgb/1341839349.873668.png 1341839349.873696 depth/1341839349.873696.png
1341839349.905746 rgb/1341839349.905746.png 1341839349.905763 depth/1341839349.905763.png
1341839349.941760 rgb/1341839349.941760.png 1341839349.941796 depth/1341839349.941796.png
1341839349.973689 rgb/1341839349.973689.png 1341839349.973701 depth/1341839349.973701.png
1341839350.009717 rgb/1341839350.009717.png 1341839350.009736 depth/1341839350.009736.png
1341839350.041679 rgb/1341839350.041679.png 1341839350.041687 depth/1341839350.041687.png
1341839350.073811 rgb/1341839350.073811.png 1341839350.073824 depth/1341839350.073824.png
1341839350.109658 rgb/1341839350.109658.png 1341839350.109678 depth/1341839350.109678.png
1341839350.141699 rgb/1341839350.141699.png 1341839350.141718 depth/1341839350.141718.png
1341839350.173592 rgb/1341839350.173592.png 1341839350.173605 depth/1341839350.173605.png
1341839350.209540 rgb/1341839350.209540.png 1341839350.209551 depth/1341839350.209551.png
1341839350.241825 rgb/1341839350.241825.png 1341839350.241827 depth/1341839350.241827.png
1341839350.280659 rgb/1341839350.280659.png 1341839350.280678 depth/1341839350.280678.png
1341839350.341753 rgb/1341839350.341753.png 1341839350.341767 depth/1341839350.341767.png
1341839350.377683 rgb/1341839350.377683.png 1341839350.377704 depth/1341839350.377704.png
1341839350.409741 rgb/1341839350.409741.png 1341839350.409792 depth/1341839350.409792.png
1341839350.441672 rgb/1341839350.441672.png 1341839350.441699 depth/1341839350.441699.png
1341839350.477741 rgb/1341839350.477741.png 1341839350.477781 depth/1341839350.477781.png
1341839350.509690 rgb/1341839350.509690.png 1341839350.509715 depth/1341839350.509715.png
1341839350.545700 rgb/1341839350.545700.png 1341839350.545709 depth/1341839350.545709.png
1341839350.577579 rgb/1341839350.577579.png 1341839350.577590 depth/1341839350.577590.png
1341839350.609742 rgb/1341839350.609742.png 1341839350.609760 depth/1341839350.609760.png
1341839350.645797 rgb/1341839350.645797.png 1341839350.645826 depth/1341839350.645826.png
1341839350.677685 rgb/1341839350.677685.png 1341839350.677708 depth/1341839350.677708.png
1341839350.713681 rgb/1341839350.713681.png 1341839350.713888 depth/1341839350.713888.png
1341839350.745657 rgb/1341839350.745657.png 1341839350.746270 depth/1341839350.746270.png
1341839350.777685 rgb/1341839350.777685.png 1341839350.777697 depth/1341839350.777697.png
1341839350.814622 rgb/1341839350.814622.png 1341839350.814726 depth/1341839350.814726.png
1341839350.845591 rgb/1341839350.845591.png 1341839350.845617 depth/1341839350.845617.png
1341839350.877688 rgb/1341839350.877688.png 1341839350.877699 depth/1341839350.877699.png
1341839350.913769 rgb/1341839350.913769.png 1341839350.913778 depth/1341839350.913778.png
1341839350.945777 rgb/1341839350.945777.png 1341839350.945791 depth/1341839350.945791.png
1341839350.981684 rgb/1341839350.981684.png 1341839350.981694 depth/1341839350.981694.png
1341839351.013674 rgb/1341839351.013674.png 1341839351.013686 depth/1341839351.013686.png
1341839351.089039 rgb/1341839351.089039.png 1341839351.089078 depth/1341839351.089078.png
1341839351.145768 rgb/1341839351.145768.png 1341839351.145779 depth/1341839351.145779.png
1341839351.181916 rgb/1341839351.181916.png 1341839351.181935 depth/1341839351.181935.png
1341839351.213695 rgb/1341839351.213695.png 1341839351.214389 depth/1341839351.214389.png
1341839351.249720 rgb/1341839351.249720.png 1341839351.250314 depth/1341839351.250314.png
1341839351.281788 rgb/1341839351.281788.png 1341839351.281815 depth/1341839351.281815.png
1341839351.313675 rgb/1341839351.313675.png 1341839351.313685 depth/1341839351.313685.png
1341839351.349751 rgb/1341839351.349751.png 1341839351.349765 depth/1341839351.349765.png
1341839351.381672 rgb/1341839351.381672.png 1341839351.381679 depth/1341839351.381679.png
1341839351.413685 rgb/1341839351.413685.png 1341839351.413696 depth/1341839351.413696.png
1341839351.449725 rgb/1341839351.449725.png 1341839351.449764 depth/1341839351.449764.png
1341839351.481707 rgb/1341839351.481707.png 1341839351.481719 depth/1341839351.481719.png
1341839351.517772 rgb/1341839351.517772.png 1341839351.517790 depth/1341839351.517790.png
1341839351.549797 rgb/1341839351.549797.png 1341839351.549827 depth/1341839351.549827.png
1341839351.581689 rgb/1341839351.581689.png 1341839351.581725 depth/1341839351.581725.png
1341839351.617604 rgb/1341839351.617604.png 1341839351.617620 depth/1341839351.617620.png
1341839351.649696 rgb/1341839351.649696.png 1341839351.649704 depth/1341839351.649704.png
1341839351.685817 rgb/1341839351.685817.png 1341839351.685834 depth/1341839351.685834.png
1341839351.717596 rgb/1341839351.717596.png 1341839351.717608 depth/1341839351.717608.png
1341839351.749639 rgb/1341839351.749639.png 1341839351.749650 depth/1341839351.749650.png
1341839351.785625 rgb/1341839351.785625.png 1341839351.785635 depth/1341839351.785635.png
1341839351.817627 rgb/1341839351.817627.png 1341839351.817647 depth/1341839351.817647.png
1341839351.849686 rgb/1341839351.849686.png 1341839351.849702 depth/1341839351.849702.png
1341839351.885694 rgb/1341839351.885694.png 1341839351.885705 depth/1341839351.885705.png
1341839351.917729 rgb/1341839351.917729.png 1341839351.917741 depth/1341839351.917741.png
1341839351.953535 rgb/1341839351.953535.png 1341839351.953548 depth/1341839351.953548.png
1341839351.985658 rgb/1341839351.985658.png 1341839351.985669 depth/1341839351.985669.png
1341839352.017647 rgb/1341839352.017647.png 1341839352.017659 depth/1341839352.017659.png
1341839352.053642 rgb/1341839352.053642.png 1341839352.053670 depth/1341839352.053670.png
1341839352.085774 rgb/1341839352.085774.png 1341839352.085784 depth/1341839352.085784.png
1341839352.117716 rgb/1341839352.117716.png 1341839352.117756 depth/1341839352.117756.png
1341839352.153646 rgb/1341839352.153646.png 1341839352.153657 depth/1341839352.153657.png
1341839352.185652 rgb/1341839352.185652.png 1341839352.185690 depth/1341839352.185690.png
1341839352.221735 rgb/1341839352.221735.png 1341839352.221755 depth/1341839352.221755.png
1341839352.253736 rgb/1341839352.253736.png 1341839352.253746 depth/1341839352.253746.png
1341839352.285752 rgb/1341839352.285752.png 1341839352.285780 depth/1341839352.285780.png
1341839352.321760 rgb/1341839352.321760.png 1341839352.321813 depth/1341839352.321813.png
1341839352.353789 rgb/1341839352.353789.png 1341839352.353802 depth/1341839352.353802.png
1341839352.385803 rgb/1341839352.385803.png 1341839352.385821 depth/1341839352.385821.png
1341839352.421731 rgb/1341839352.421731.png 1341839352.421743 depth/1341839352.421743.png
1341839352.453683 rgb/1341839352.453683.png 1341839352.454124 depth/1341839352.454124.png
1341839352.489870 rgb/1341839352.489870.png 1341839352.489884 depth/1341839352.489884.png
1341839352.521781 rgb/1341839352.521781.png 1341839352.521799 depth/1341839352.521799.png
1341839352.553740 rgb/1341839352.553740.png 1341839352.554196 depth/1341839352.554196.png
1341839352.592712 rgb/1341839352.592712.png 1341839352.592733 depth/1341839352.592733.png
1341839352.653962 rgb/1341839352.653962.png 1341839352.653982 depth/1341839352.653982.png
1341839352.692715 rgb/1341839352.692715.png 1341839352.692762 depth/1341839352.692762.png
1341839352.757603 rgb/1341839352.757603.png 1341839352.757652 depth/1341839352.757652.png
1341839352.792571 rgb/1341839352.792571.png 1341839352.792612 depth/1341839352.792612.png
1341839352.857762 rgb/1341839352.857762.png 1341839352.857774 depth/1341839352.857774.png
1341839352.889879 rgb/1341839352.889879.png 1341839352.889975 depth/1341839352.889975.png
1341839352.925639 rgb/1341839352.925639.png 1341839352.925653 depth/1341839352.925653.png
1341839352.960824 rgb/1341839352.960824.png 1341839352.960853 depth/1341839352.960853.png
1341839353.025681 rgb/1341839353.025681.png 1341839353.025694 depth/1341839353.025694.png
1341839353.057719 rgb/1341839353.057719.png 1341839353.057737 depth/1341839353.057737.png
1341839353.089820 rgb/1341839353.089820.png 1341839353.089840 depth/1341839353.089840.png
1341839353.125813 rgb/1341839353.125813.png 1341839353.125824 depth/1341839353.125824.png
1341839353.157710 rgb/1341839353.157710.png 1341839353.157719 depth/1341839353.157719.png
1341839353.193938 rgb/1341839353.193938.png 1341839353.194047 depth/1341839353.194047.png
1341839353.225679 rgb/1341839353.225679.png 1341839353.225693 depth/1341839353.225693.png
1341839353.257913 rgb/1341839353.257913.png 1341839353.257937 depth/1341839353.257937.png
1341839353.296780 rgb/1341839353.296780.png 1341839353.296799 depth/1341839353.296799.png
1341839353.335548 rgb/1341839353.335548.png 1341839353.335584 depth/1341839353.335584.png
1341839353.364651 rgb/1341839353.364651.png 1341839353.364885 depth/1341839353.364885.png
1341839353.400728 rgb/1341839353.400728.png 1341839353.400775 depth/1341839353.400775.png
1341839353.432721 rgb/1341839353.432721.png 1341839353.432737 depth/1341839353.432737.png
1341839353.464780 rgb/1341839353.464780.png 1341839353.464794 depth/1341839353.464794.png
1341839353.500713 rgb/1341839353.500713.png 1341839353.500731 depth/1341839353.500731.png
1341839353.532682 rgb/1341839353.532682.png 1341839353.532694 depth/1341839353.532694.png
1341839353.568645 rgb/1341839353.568645.png 1341839353.568655 depth/1341839353.568655.png
1341839353.600681 rgb/1341839353.600681.png 1341839353.600699 depth/1341839353.600699.png
1341839353.663071 rgb/1341839353.663071.png 1341839353.663133 depth/1341839353.663133.png
1341839353.693949 rgb/1341839353.693949.png 1341839353.694757 depth/1341839353.694757.png
1341839353.729827 rgb/1341839353.729827.png 1341839353.729840 depth/1341839353.729840.png
1341839353.761755 rgb/1341839353.761755.png 1341839353.762769 depth/1341839353.762769.png
1341839353.794339 rgb/1341839353.794339.png 1341839353.794377 depth/1341839353.794377.png
1341839353.838084 rgb/1341839353.838084.png 1341839353.838101 depth/1341839353.838101.png
1341839353.900785 rgb/1341839353.900785.png 1341839353.900821 depth/1341839353.900821.png
1341839353.961728 rgb/1341839353.961728.png 1341839353.961940 depth/1341839353.961940.png
1341839354.000918 rgb/1341839354.000918.png 1341839354.002030 depth/1341839354.002030.png
1341839354.037947 rgb/1341839354.037947.png 1341839354.039276 depth/1341839354.039276.png
1341839354.069412 rgb/1341839354.069412.png 1341839354.069798 depth/1341839354.069798.png
1341839354.136797 rgb/1341839354.136797.png 1341839354.136831 depth/1341839354.136831.png
1341839354.197963 rgb/1341839354.197963.png 1341839354.198709 depth/1341839354.198709.png
1341839354.229618 rgb/1341839354.229618.png 1341839354.229653 depth/1341839354.229653.png
1341839354.265633 rgb/1341839354.265633.png 1341839354.265645 depth/1341839354.265645.png
1341839354.298363 rgb/1341839354.298363.png 1341839354.297874 depth/1341839354.297874.png
1341839354.329689 rgb/1341839354.329689.png 1341839354.329700 depth/1341839354.329700.png
1341839354.366365 rgb/1341839354.366365.png 1341839354.366440 depth/1341839354.366440.png
1341839354.397620 rgb/1341839354.397620.png 1341839354.397631 depth/1341839354.397631.png
1341839354.433710 rgb/1341839354.433710.png 1341839354.433728 depth/1341839354.433728.png
1341839354.465713 rgb/1341839354.465713.png 1341839354.465726 depth/1341839354.465726.png
1341839354.497576 rgb/1341839354.497576.png 1341839354.497590 depth/1341839354.497590.png
1341839354.533748 rgb/1341839354.533748.png 1341839354.533790 depth/1341839354.533790.png
1341839354.565577 rgb/1341839354.565577.png 1341839354.565585 depth/1341839354.565585.png
1341839354.597692 rgb/1341839354.597692.png 1341839354.597739 depth/1341839354.597739.png
1341839354.633605 rgb/1341839354.633605.png 1341839354.633631 depth/1341839354.633631.png
1341839354.665643 rgb/1341839354.665643.png 1341839354.665662 depth/1341839354.665662.png
1341839354.701714 rgb/1341839354.701714.png 1341839354.701725 depth/1341839354.701725.png
1341839354.733804 rgb/1341839354.733804.png 1341839354.733850 depth/1341839354.733850.png
1341839354.765616 rgb/1341839354.765616.png 1341839354.765676 depth/1341839354.765676.png
1341839354.801679 rgb/1341839354.801679.png 1341839354.801718 depth/1341839354.801718.png
1341839354.833771 rgb/1341839354.833771.png 1341839354.833783 depth/1341839354.833783.png
1341839354.865631 rgb/1341839354.865631.png 1341839354.865709 depth/1341839354.865709.png
1341839354.901651 rgb/1341839354.901651.png 1341839354.901667 depth/1341839354.901667.png
1341839354.933716 rgb/1341839354.933716.png 1341839354.934160 depth/1341839354.934160.png
1341839354.969646 rgb/1341839354.969646.png 1341839354.969722 depth/1341839354.969722.png
1341839355.001713 rgb/1341839355.001713.png 1341839355.001769 depth/1341839355.001769.png
1341839355.033725 rgb/1341839355.033725.png 1341839355.033737 depth/1341839355.033737.png
1341839355.069603 rgb/1341839355.069603.png 1341839355.069614 depth/1341839355.069614.png
1341839355.101627 rgb/1341839355.101627.png 1341839355.101644 depth/1341839355.101644.png
1341839355.137531 rgb/1341839355.137531.png 1341839355.137540 depth/1341839355.137540.png
1341839355.169562 rgb/1341839355.169562.png 1341839355.169571 depth/1341839355.169571.png
1341839355.201760 rgb/1341839355.201760.png 1341839355.201782 depth/1341839355.201782.png
1341839355.237695 rgb/1341839355.237695.png 1341839355.237716 depth/1341839355.237716.png
1341839355.269652 rgb/1341839355.269652.png 1341839355.269692 depth/1341839355.269692.png
1341839355.301616 rgb/1341839355.301616.png 1341839355.301664 depth/1341839355.301664.png
1341839355.337610 rgb/1341839355.337610.png 1341839355.337641 depth/1341839355.337641.png
1341839355.369612 rgb/1341839355.369612.png 1341839355.369662 depth/1341839355.369662.png
1341839355.405623 rgb/1341839355.405623.png 1341839355.405658 depth/1341839355.405658.png
1341839355.437629 rgb/1341839355.437629.png 1341839355.437662 depth/1341839355.437662.png
1341839355.469756 rgb/1341839355.469756.png 1341839355.469766 depth/1341839355.469766.png
1341839355.505688 rgb/1341839355.505688.png 1341839355.505709 depth/1341839355.505709.png
1341839355.537644 rgb/1341839355.537644.png 1341839355.537653 depth/1341839355.537653.png
1341839355.569700 rgb/1341839355.569700.png 1341839355.569708 depth/1341839355.569708.png
1341839355.605650 rgb/1341839355.605650.png 1341839355.605674 depth/1341839355.605674.png
1341839355.637626 rgb/1341839355.637626.png 1341839355.637635 depth/1341839355.637635.png
1341839355.673784 rgb/1341839355.673784.png 1341839355.673801 depth/1341839355.673801.png
1341839355.706249 rgb/1341839355.706249.png 1341839355.706928 depth/1341839355.706928.png
1341839355.739256 rgb/1341839355.739256.png 1341839355.739271 depth/1341839355.739271.png
1341839355.774017 rgb/1341839355.774017.png 1341839355.774038 depth/1341839355.774038.png
1341839355.806602 rgb/1341839355.806602.png 1341839355.807663 depth/1341839355.807663.png
1341839355.838477 rgb/1341839355.838477.png 1341839355.840813 depth/1341839355.840813.png
1341839355.876285 rgb/1341839355.876285.png 1341839355.877042 depth/1341839355.877042.png
1341839355.909298 rgb/1341839355.909298.png 1341839355.909353 depth/1341839355.909353.png
1341839355.942206 rgb/1341839355.942206.png 1341839355.942231 depth/1341839355.942231.png
1341839355.974188 rgb/1341839355.974188.png 1341839355.975397 depth/1341839355.975397.png
1341839356.041846 rgb/1341839356.041846.png 1341839356.041875 depth/1341839356.041875.png
1341839356.073656 rgb/1341839356.073656.png 1341839356.073705 depth/1341839356.073705.png
1341839356.109615 rgb/1341839356.109615.png 1341839356.109646 depth/1341839356.109646.png
1341839356.141597 rgb/1341839356.141597.png 1341839356.141613 depth/1341839356.141613.png
1341839356.173684 rgb/1341839356.173684.png 1341839356.173695 depth/1341839356.173695.png
1341839356.209613 rgb/1341839356.209613.png 1341839356.209623 depth/1341839356.209623.png
1341839356.241782 rgb/1341839356.241782.png 1341839356.241797 depth/1341839356.241797.png
1341839356.273675 rgb/1341839356.273675.png 1341839356.273709 depth/1341839356.273709.png
1341839356.309726 rgb/1341839356.309726.png 1341839356.309737 depth/1341839356.309737.png
1341839356.342087 rgb/1341839356.342087.png 1341839356.342107 depth/1341839356.342107.png
1341839356.377564 rgb/1341839356.377564.png 1341839356.377576 depth/1341839356.377576.png
1341839356.409691 rgb/1341839356.409691.png 1341839356.409746 depth/1341839356.409746.png
1341839356.441698 rgb/1341839356.441698.png 1341839356.441728 depth/1341839356.441728.png
1341839356.477584 rgb/1341839356.477584.png 1341839356.477618 depth/1341839356.477618.png
1341839356.509645 rgb/1341839356.509645.png 1341839356.509661 depth/1341839356.509661.png
1341839356.541706 rgb/1341839356.541706.png 1341839356.541721 depth/1341839356.541721.png
1341839356.577608 rgb/1341839356.577608.png 1341839356.577645 depth/1341839356.577645.png
1341839356.609837 rgb/1341839356.609837.png 1341839356.609851 depth/1341839356.609851.png
1341839356.645735 rgb/1341839356.645735.png 1341839356.645767 depth/1341839356.645767.png
1341839356.677975 rgb/1341839356.677975.png 1341839356.678001 depth/1341839356.678001.png
1341839356.709843 rgb/1341839356.709843.png 1341839356.710350 depth/1341839356.710350.png
1341839356.745847 rgb/1341839356.745847.png 1341839356.745869 depth/1341839356.745869.png
1341839356.777774 rgb/1341839356.777774.png 1341839356.777797 depth/1341839356.777797.png
1341839356.809802 rgb/1341839356.809802.png 1341839356.809816 depth/1341839356.809816.png
1341839356.845719 rgb/1341839356.845719.png 1341839356.845743 depth/1341839356.845743.png
1341839356.877710 rgb/1341839356.877710.png 1341839356.877920 depth/1341839356.877920.png
1341839356.913747 rgb/1341839356.913747.png 1341839356.913773 depth/1341839356.913773.png
1341839356.945651 rgb/1341839356.945651.png 1341839356.945674 depth/1341839356.945674.png
1341839356.978052 rgb/1341839356.978052.png 1341839356.978071 depth/1341839356.978071.png
1341839357.013861 rgb/1341839357.013861.png 1341839357.013875 depth/1341839357.013875.png
1341839357.046107 rgb/1341839357.046107.png 1341839357.046119 depth/1341839357.046119.png
1341839357.077622 rgb/1341839357.077622.png 1341839357.077637 depth/1341839357.077637.png
1341839357.113806 rgb/1341839357.113806.png 1341839357.113828 depth/1341839357.113828.png
1341839357.146224 rgb/1341839357.146224.png 1341839357.146265 depth/1341839357.146265.png
1341839357.181674 rgb/1341839357.181674.png 1341839357.181688 depth/1341839357.181688.png
1341839357.213755 rgb/1341839357.213755.png 1341839357.213772 depth/1341839357.213772.png
1341839357.245802 rgb/1341839357.245802.png 1341839357.245874 depth/1341839357.245874.png
1341839357.281655 rgb/1341839357.281655.png 1341839357.281713 depth/1341839357.281713.png
1341839357.313687 rgb/1341839357.313687.png 1341839357.313694 depth/1341839357.313694.png
1341839357.349654 rgb/1341839357.349654.png 1341839357.349699 depth/1341839357.349699.png
1341839357.381649 rgb/1341839357.381649.png 1341839357.381667 depth/1341839357.381667.png
1341839357.413668 rgb/1341839357.413668.png 1341839357.413685 depth/1341839357.413685.png
1341839357.449913 rgb/1341839357.449913.png 1341839357.449934 depth/1341839357.449934.png
1341839357.481703 rgb/1341839357.481703.png 1341839357.481712 depth/1341839357.481712.png
1341839357.514956 rgb/1341839357.514956.png 1341839357.514990 depth/1341839357.514990.png
1341839357.549716 rgb/1341839357.549716.png 1341839357.549742 depth/1341839357.549742.png
1341839357.581581 rgb/1341839357.581581.png 1341839357.581606 depth/1341839357.581606.png
1341839357.617637 rgb/1341839357.617637.png 1341839357.617709 depth/1341839357.617709.png
1341839357.649685 rgb/1341839357.649685.png 1341839357.649699 depth/1341839357.649699.png
1341839357.681786 rgb/1341839357.681786.png 1341839357.681817 depth/1341839357.681817.png
1341839357.717826 rgb/1341839357.717826.png 1341839357.717860 depth/1341839357.717860.png
1341839357.749655 rgb/1341839357.749655.png 1341839357.749666 depth/1341839357.749666.png
1341839357.781624 rgb/1341839357.781624.png 1341839357.781642 depth/1341839357.781642.png
1341839357.817786 rgb/1341839357.817786.png 1341839357.817823 depth/1341839357.817823.png
1341839357.849783 rgb/1341839357.849783.png 1341839357.849808 depth/1341839357.849808.png
1341839357.885712 rgb/1341839357.885712.png 1341839357.885736 depth/1341839357.885736.png
1341839357.917712 rgb/1341839357.917712.png 1341839357.917751 depth/1341839357.917751.png
1341839357.949667 rgb/1341839357.949667.png 1341839357.949690 depth/1341839357.949690.png
1341839357.985579 rgb/1341839357.985579.png 1341839357.985623 depth/1341839357.985623.png
1341839358.017628 rgb/1341839358.017628.png 1341839358.017650 depth/1341839358.017650.png
1341839358.049615 rgb/1341839358.049615.png 1341839358.049655 depth/1341839358.049655.png
1341839358.085696 rgb/1341839358.085696.png 1341839358.085737 depth/1341839358.085737.png
1341839358.117598 rgb/1341839358.117598.png 1341839358.117637 depth/1341839358.117637.png
1341839358.153682 rgb/1341839358.153682.png 1341839358.153715 depth/1341839358.153715.png
1341839358.185801 rgb/1341839358.185801.png 1341839358.185844 depth/1341839358.185844.png
1341839358.217780 rgb/1341839358.217780.png 1341839358.217797 depth/1341839358.217797.png
1341839358.253603 rgb/1341839358.253603.png 1341839358.253652 depth/1341839358.253652.png
1341839358.285662 rgb/1341839358.285662.png 1341839358.285679 depth/1341839358.285679.png
1341839358.321840 rgb/1341839358.321840.png 1341839358.321849 depth/1341839358.321849.png
1341839358.353833 rgb/1341839358.353833.png 1341839358.353846 depth/1341839358.353846.png
1341839358.385678 rgb/1341839358.385678.png 1341839358.385731 depth/1341839358.385731.png
1341839358.428788 rgb/1341839358.428788.png 1341839358.428825 depth/1341839358.428825.png
1341839358.485712 rgb/1341839358.485712.png 1341839358.485748 depth/1341839358.485748.png
1341839358.521878 rgb/1341839358.521878.png 1341839358.521915 depth/1341839358.521915.png
1341839358.554882 rgb/1341839358.554882.png 1341839358.554900 depth/1341839358.554900.png
1341839358.589750 rgb/1341839358.589750.png 1341839358.589775 depth/1341839358.589775.png
1341839358.621635 rgb/1341839358.621635.png 1341839358.621650 depth/1341839358.621650.png
1341839358.653698 rgb/1341839358.653698.png 1341839358.653706 depth/1341839358.653706.png
1341839358.689793 rgb/1341839358.689793.png 1341839358.689824 depth/1341839358.689824.png
1341839358.721862 rgb/1341839358.721862.png 1341839358.721953 depth/1341839358.721953.png
1341839358.753842 rgb/1341839358.753842.png 1341839358.753862 depth/1341839358.753862.png
1341839358.789992 rgb/1341839358.789992.png 1341839358.790019 depth/1341839358.790019.png
1341839358.821835 rgb/1341839358.821835.png 1341839358.822338 depth/1341839358.822338.png
1341839358.857631 rgb/1341839358.857631.png 1341839358.857645 depth/1341839358.857645.png
1341839358.889695 rgb/1341839358.889695.png 1341839358.890250 depth/1341839358.890250.png
1341839358.921673 rgb/1341839358.921673.png 1341839358.921681 depth/1341839358.921681.png
1341839358.957766 rgb/1341839358.957766.png 1341839358.957797 depth/1341839358.957797.png
1341839358.989751 rgb/1341839358.989751.png 1341839358.989760 depth/1341839358.989760.png
1341839359.021755 rgb/1341839359.021755.png 1341839359.021775 depth/1341839359.021775.png
1341839359.058178 rgb/1341839359.058178.png 1341839359.058198 depth/1341839359.058198.png
1341839359.089826 rgb/1341839359.089826.png 1341839359.090576 depth/1341839359.090576.png
1341839359.125660 rgb/1341839359.125660.png 1341839359.125670 depth/1341839359.125670.png
1341839359.157759 rgb/1341839359.157759.png 1341839359.157815 depth/1341839359.157815.png
1341839359.189872 rgb/1341839359.189872.png 1341839359.189878 depth/1341839359.189878.png
1341839359.225681 rgb/1341839359.225681.png 1341839359.225701 depth/1341839359.225701.png
1341839359.257807 rgb/1341839359.257807.png 1341839359.257833 depth/1341839359.257833.png
1341839359.289681 rgb/1341839359.289681.png 1341839359.289696 depth/1341839359.289696.png
1341839359.325714 rgb/1341839359.325714.png 1341839359.325740 depth/1341839359.325740.png
1341839359.357757 rgb/1341839359.357757.png 1341839359.357773 depth/1341839359.357773.png
1341839359.393776 rgb/1341839359.393776.png 1341839359.393816 depth/1341839359.393816.png
1341839359.425642 rgb/1341839359.425642.png 1341839359.425656 depth/1341839359.425656.png
1341839359.457813 rgb/1341839359.457813.png 1341839359.457834 depth/1341839359.457834.png
1341839359.493829 rgb/1341839359.493829.png 1341839359.493854 depth/1341839359.493854.png
1341839359.525779 rgb/1341839359.525779.png 1341839359.525792 depth/1341839359.525792.png
1341839359.561710 rgb/1341839359.561710.png 1341839359.561753 depth/1341839359.561753.png
1341839359.593664 rgb/1341839359.593664.png 1341839359.593701 depth/1341839359.593701.png
1341839359.625670 rgb/1341839359.625670.png 1341839359.625855 depth/1341839359.625855.png
1341839359.661897 rgb/1341839359.661897.png 1341839359.661931 depth/1341839359.661931.png
1341839359.694301 rgb/1341839359.694301.png 1341839359.694317 depth/1341839359.694317.png
1341839359.725642 rgb/1341839359.725642.png 1341839359.725654 depth/1341839359.725654.png
1341839359.761750 rgb/1341839359.761750.png 1341839359.761764 depth/1341839359.761764.png
1341839359.793758 rgb/1341839359.793758.png 1341839359.793778 depth/1341839359.793778.png
1341839359.829704 rgb/1341839359.829704.png 1341839359.829763 depth/1341839359.829763.png
1341839359.861791 rgb/1341839359.861791.png 1341839359.861821 depth/1341839359.861821.png
1341839359.893777 rgb/1341839359.893777.png 1341839359.893806 depth/1341839359.893806.png
1341839359.929739 rgb/1341839359.929739.png 1341839359.929773 depth/1341839359.929773.png
1341839359.961705 rgb/1341839359.961705.png 1341839359.961730 depth/1341839359.961730.png
1341839359.993730 rgb/1341839359.993730.png 1341839359.993743 depth/1341839359.993743.png
1341839360.029709 rgb/1341839360.029709.png 1341839360.029722 depth/1341839360.029722.png
1341839360.061822 rgb/1341839360.061822.png 1341839360.062441 depth/1341839360.062441.png
1341839360.100893 rgb/1341839360.100893.png 1341839360.100910 depth/1341839360.100910.png
1341839360.137502 rgb/1341839360.137502.png 1341839360.138191 depth/1341839360.138191.png
1341839360.201017 rgb/1341839360.201017.png 1341839360.202419 depth/1341839360.202419.png
1341839360.236907 rgb/1341839360.236907.png 1341839360.237476 depth/1341839360.237476.png
1341839360.269741 rgb/1341839360.269741.png 1341839360.270870 depth/1341839360.270870.png
1341839360.305127 rgb/1341839360.305127.png 1341839360.305510 depth/1341839360.305510.png
1341839360.337161 rgb/1341839360.337161.png 1341839360.337571 depth/1341839360.337571.png
1341839360.371370 rgb/1341839360.371370.png 1341839360.373429 depth/1341839360.373429.png
1341839360.404790 rgb/1341839360.404790.png 1341839360.404820 depth/1341839360.404820.png
1341839360.473022 rgb/1341839360.473022.png 1341839360.473319 depth/1341839360.473319.png
1341839360.533749 rgb/1341839360.533749.png 1341839360.533800 depth/1341839360.533800.png
1341839360.565788 rgb/1341839360.565788.png 1341839360.565814 depth/1341839360.565814.png
1341839360.597615 rgb/1341839360.597615.png 1341839360.597672 depth/1341839360.597672.png
1341839360.633615 rgb/1341839360.633615.png 1341839360.633651 depth/1341839360.633651.png
1341839360.665699 rgb/1341839360.665699.png 1341839360.665719 depth/1341839360.665719.png
1341839360.697767 rgb/1341839360.697767.png 1341839360.697813 depth/1341839360.697813.png
1341839360.733659 rgb/1341839360.733659.png 1341839360.733668 depth/1341839360.733668.png
1341839360.765779 rgb/1341839360.765779.png 1341839360.765793 depth/1341839360.765793.png
1341839360.801691 rgb/1341839360.801691.png 1341839360.801703 depth/1341839360.801703.png
1341839360.833754 rgb/1341839360.833754.png 1341839360.833770 depth/1341839360.833770.png
1341839360.865719 rgb/1341839360.865719.png 1341839360.865733 depth/1341839360.865733.png
1341839360.901694 rgb/1341839360.901694.png 1341839360.901705 depth/1341839360.901705.png
1341839360.965710 rgb/1341839360.965710.png 1341839360.965737 depth/1341839360.965737.png
1341839361.002295 rgb/1341839361.002295.png 1341839361.002321 depth/1341839361.002321.png
1341839361.033764 rgb/1341839361.033764.png 1341839361.034750 depth/1341839361.034750.png
1341839361.102289 rgb/1341839361.102289.png 1341839361.103706 depth/1341839361.103706.png
1341839361.169771 rgb/1341839361.169771.png 1341839361.169933 depth/1341839361.169933.png
1341839361.201803 rgb/1341839361.201803.png 1341839361.201826 depth/1341839361.201826.png
1341839361.233892 rgb/1341839361.233892.png 1341839361.233920 depth/1341839361.233920.png
1341839361.269677 rgb/1341839361.269677.png 1341839361.269703 depth/1341839361.269703.png
1341839361.301795 rgb/1341839361.301795.png 1341839361.301843 depth/1341839361.301843.png
1341839361.337636 rgb/1341839361.337636.png 1341839361.337686 depth/1341839361.337686.png
1341839361.369704 rgb/1341839361.369704.png 1341839361.369755 depth/1341839361.369755.png
1341839361.401585 rgb/1341839361.401585.png 1341839361.401618 depth/1341839361.401618.png
1341839361.437714 rgb/1341839361.437714.png 1341839361.437742 depth/1341839361.437742.png
1341839361.469733 rgb/1341839361.469733.png 1341839361.469756 depth/1341839361.469756.png
1341839361.501602 rgb/1341839361.501602.png 1341839361.501612 depth/1341839361.501612.png
1341839361.537692 rgb/1341839361.537692.png 1341839361.537722 depth/1341839361.537722.png
1341839361.569984 rgb/1341839361.569984.png 1341839361.570767 depth/1341839361.570767.png
1341839361.606542 rgb/1341839361.606542.png 1341839361.607329 depth/1341839361.607329.png
1341839361.637785 rgb/1341839361.637785.png 1341839361.637921 depth/1341839361.637921.png
1341839361.708797 rgb/1341839361.708797.png 1341839361.708855 depth/1341839361.708855.png
1341839361.773788 rgb/1341839361.773788.png 1341839361.773844 depth/1341839361.773844.png
1341839361.805940 rgb/1341839361.805940.png 1341839361.805953 depth/1341839361.805953.png
1341839361.837711 rgb/1341839361.837711.png 1341839361.838183 depth/1341839361.838183.png
1341839361.873794 rgb/1341839361.873794.png 1341839361.874230 depth/1341839361.874230.png
1341839361.905952 rgb/1341839361.905952.png 1341839361.905976 depth/1341839361.905976.png
1341839361.937751 rgb/1341839361.937751.png 1341839361.937796 depth/1341839361.937796.png
1341839361.973665 rgb/1341839361.973665.png 1341839361.973701 depth/1341839361.973701.png
1341839362.041782 rgb/1341839362.041782.png 1341839362.041796 depth/1341839362.041796.png
1341839362.073669 rgb/1341839362.073669.png 1341839362.073699 depth/1341839362.073699.png
1341839362.105771 rgb/1341839362.105771.png 1341839362.105993 depth/1341839362.105993.png
1341839362.141801 rgb/1341839362.141801.png 1341839362.141822 depth/1341839362.141822.png
1341839362.173951 rgb/1341839362.173951.png 1341839362.173985 depth/1341839362.173985.png
1341839362.205868 rgb/1341839362.205868.png 1341839362.205875 depth/1341839362.205875.png
1341839362.244834 rgb/1341839362.244834.png 1341839362.244887 depth/1341839362.244887.png
1341839362.309766 rgb/1341839362.309766.png 1341839362.309785 depth/1341839362.309785.png
1341839362.342256 rgb/1341839362.342256.png 1341839362.342269 depth/1341839362.342269.png
1341839362.375616 rgb/1341839362.375616.png 1341839362.376908 depth/1341839362.376908.png
1341839362.409857 rgb/1341839362.409857.png 1341839362.411098 depth/1341839362.411098.png
1341839362.441822 rgb/1341839362.441822.png 1341839362.441894 depth/1341839362.441894.png
1341839362.473901 rgb/1341839362.473901.png 1341839362.473911 depth/1341839362.473911.png
1341839362.509593 rgb/1341839362.509593.png 1341839362.509604 depth/1341839362.509604.png
1341839362.542222 rgb/1341839362.542222.png 1341839362.542263 depth/1341839362.542263.png
1341839362.577899 rgb/1341839362.577899.png 1341839362.577920 depth/1341839362.577920.png
1341839362.617020 rgb/1341839362.617020.png 1341839362.617027 depth/1341839362.617027.png
1341839362.649367 rgb/1341839362.649367.png 1341839362.649381 depth/1341839362.649381.png
1341839362.680746 rgb/1341839362.680746.png 1341839362.680757 depth/1341839362.680757.png
1341839362.716791 rgb/1341839362.716791.png 1341839362.716808 depth/1341839362.716808.png
1341839362.748669 rgb/1341839362.748669.png 1341839362.748683 depth/1341839362.748683.png
1341839362.784599 rgb/1341839362.784599.png 1341839362.784611 depth/1341839362.784611.png
1341839362.816854 rgb/1341839362.816854.png 1341839362.817010 depth/1341839362.817010.png
1341839362.848682 rgb/1341839362.848682.png 1341839362.848690 depth/1341839362.848690.png
1341839362.884649 rgb/1341839362.884649.png 1341839362.884665 depth/1341839362.884665.png
1341839362.916705 rgb/1341839362.916705.png 1341839362.916719 depth/1341839362.916719.png
1341839362.952721 rgb/1341839362.952721.png 1341839362.952744 depth/1341839362.952744.png
1341839362.984800 rgb/1341839362.984800.png 1341839362.984817 depth/1341839362.984817.png
1341839363.016641 rgb/1341839363.016641.png 1341839363.016656 depth/1341839363.016656.png
1341839363.052753 rgb/1341839363.052753.png 1341839363.052768 depth/1341839363.052768.png
1341839363.084836 rgb/1341839363.084836.png 1341839363.084854 depth/1341839363.084854.png
1341839363.120807 rgb/1341839363.120807.png 1341839363.120843 depth/1341839363.120843.png
1341839363.152777 rgb/1341839363.152777.png 1341839363.152798 depth/1341839363.152798.png
1341839363.184689 rgb/1341839363.184689.png 1341839363.184717 depth/1341839363.184717.png
1341839363.220783 rgb/1341839363.220783.png 1341839363.220795 depth/1341839363.220795.png
1341839363.252646 rgb/1341839363.252646.png 1341839363.252661 depth/1341839363.252661.png
1341839363.288713 rgb/1341839363.288713.png 1341839363.289488 depth/1341839363.289488.png
1341839363.320693 rgb/1341839363.320693.png 1341839363.320701 depth/1341839363.320701.png
1341839363.352718 rgb/1341839363.352718.png 1341839363.352737 depth/1341839363.352737.png
1341839363.388705 rgb/1341839363.388705.png 1341839363.388748 depth/1341839363.388748.png
1341839363.420746 rgb/1341839363.420746.png 1341839363.420760 depth/1341839363.420760.png
1341839363.452892 rgb/1341839363.452892.png 1341839363.452907 depth/1341839363.452907.png
1341839363.488698 rgb/1341839363.488698.png 1341839363.488720 depth/1341839363.488720.png
1341839363.520896 rgb/1341839363.520896.png 1341839363.520904 depth/1341839363.520904.png
1341839363.556670 rgb/1341839363.556670.png 1341839363.556678 depth/1341839363.556678.png
1341839363.588697 rgb/1341839363.588697.png 1341839363.588713 depth/1341839363.588713.png
1341839363.620692 rgb/1341839363.620692.png 1341839363.621300 depth/1341839363.621300.png
1341839363.656709 rgb/1341839363.656709.png 1341839363.656723 depth/1341839363.656723.png
1341839363.713762 rgb/1341839363.713762.png 1341839363.713784 depth/1341839363.713784.png
1341839363.749603 rgb/1341839363.749603.png 1341839363.749630 depth/1341839363.749630.png
1341839363.781800 rgb/1341839363.781800.png 1341839363.781815 depth/1341839363.781815.png
1341839363.817716 rgb/1341839363.817716.png 1341839363.818286 depth/1341839363.818286.png
1341839363.849637 rgb/1341839363.849637.png 1341839363.849647 depth/1341839363.849647.png
1341839363.881770 rgb/1341839363.881770.png 1341839363.881834 depth/1341839363.881834.png
1341839363.917738 rgb/1341839363.917738.png 1341839363.917748 depth/1341839363.917748.png
1341839363.949778 rgb/1341839363.949778.png 1341839363.949819 depth/1341839363.949819.png
1341839363.985613 rgb/1341839363.985613.png 1341839363.985653 depth/1341839363.985653.png
1341839364.017747 rgb/1341839364.017747.png 1341839364.017757 depth/1341839364.017757.png
1341839364.049835 rgb/1341839364.049835.png 1341839364.049845 depth/1341839364.049845.png
1341839364.085694 rgb/1341839364.085694.png 1341839364.085748 depth/1341839364.085748.png
1341839364.117765 rgb/1341839364.117765.png 1341839364.117780 depth/1341839364.117780.png
1341839364.149652 rgb/1341839364.149652.png 1341839364.149747 depth/1341839364.149747.png
1341839364.185672 rgb/1341839364.185672.png 1341839364.185688 depth/1341839364.185688.png
1341839364.217809 rgb/1341839364.217809.png 1341839364.217822 depth/1341839364.217822.png
1341839364.253809 rgb/1341839364.253809.png 1341839364.253826 depth/1341839364.253826.png
1341839364.285702 rgb/1341839364.285702.png 1341839364.286246 depth/1341839364.286246.png
1341839364.317689 rgb/1341839364.317689.png 1341839364.317704 depth/1341839364.317704.png
1341839364.353709 rgb/1341839364.353709.png 1341839364.353723 depth/1341839364.353723.png
1341839364.385786 rgb/1341839364.385786.png 1341839364.385804 depth/1341839364.385804.png
================================================
FILE: Examples/RGB-D/kinect.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 517.306
Camera.fy: 516.469
Camera.cx: 318.643
Camera.cy: 255.313
Camera.k1: 0
Camera.k2: -0.0
Camera.p1: -0.000
Camera.p2: 0.000
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30.0
# IR projector baseline times fx (aprox.)
Camera.bf: 25
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 0
# Close/Far threshold. Baseline times.
ThDepth: 6.0
# Deptmap values factor
DepthMapFactor: 1000.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 5000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.5
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 4
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/RGB-D/rgbd_live.cpp
================================================
#include
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strAssociationFilename, vector &vstrImageFilenamesRGB,
vector &vstrImageFilenamesD, vector &vTimestamps);
int main(int argc, char **argv)
{
if(argc != 4)
{
cerr << endl << "Usage: ./rgbd_live path_to_settings path_to_sequence" << endl;
return 1;
}
std::string str_vocab = argv[1];
std::string str_settings = argv[2];
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(str_vocab,str_settings,Jetson_SLAM::System::RGBD,true);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
// Main loop
cv::Mat imRGB, imD;
cv::VideoCapture v_rgb = cv::VideoCapture("output.avi");
cv::VideoCapture v_depth = cv::VideoCapture("depth.mkv");
v_depth.set(cv::CAP_PROP_CONVERT_RGB, 0);
int id = 0;
while(1)
{
v_rgb >> imRGB;
v_depth >> imD;
if(imRGB.empty())
{
cerr << endl << "video is empty" << endl;
return 1;
}
double tframe = std::time(0);// vTimestamps[ni];
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#endif
// Pass the images to the SLAM system
cv::Mat pose = SLAM.TrackRGBD(imRGB,imD,tframe);
if(!pose.empty())
std::cout << pose << "\n";
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#endif
double ttrack= std::chrono::duration_cast >(t2 - t1).count();
usleep(1000);
}
// Stop all threads
SLAM.Shutdown();
// // Tracking time statistics
// sort(vTimesTrack.begin(),vTimesTrack.end());
// float totaltime = 0;
// for(int ni=0; ni (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strAssociationFilename, vector &vstrImageFilenamesRGB,
vector &vstrImageFilenamesD, vector &vTimestamps);
int main(int argc, char **argv)
{
if(argc != 5)
{
cerr << endl << "Usage: ./rgbd_tum path_to_vocabulary path_to_settings path_to_sequence path_to_association" << endl;
return 1;
}
std::string str_vocab = argv[1];;
std::string str_settings = argv[2];
std::string str_seq_path = argv[3];
std::string str_association_path = argv[4];
// Retrieve paths to images
vector vstrImageFilenamesRGB;
vector vstrImageFilenamesD;
vector vTimestamps;
string strAssociationFilename = argv[4];
LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps);
// Check consistency in the number of images and depthmaps
int nImages = vstrImageFilenamesRGB.size();
if(vstrImageFilenamesRGB.empty())
{
cerr << endl << "No images found in provided path." << endl;
return 1;
}
else if(vstrImageFilenamesD.size()!=vstrImageFilenamesRGB.size())
{
cerr << endl << "Different number of images for rgb and depth." << endl;
return 1;
}
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(str_vocab,str_settings, Jetson_SLAM::System::RGBD,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
// Main loop
cv::Mat imRGB, imD;
for(int ni=0; ni >(t2 - t1).count();
vTimesTrack[ni]=ttrack;
// Wait to load the next frame
double T=0;
if(ni0)
T = tframe-vTimestamps[ni-1];
if(ttrack &vstrImageFilenamesRGB,
vector &vstrImageFilenamesD, vector &vTimestamps)
{
ifstream fAssociation;
fAssociation.open(strAssociationFilename.c_str());
while(!fAssociation.eof())
{
string s;
getline(fAssociation,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t;
string sRGB, sD;
ss >> t;
vTimestamps.push_back(t);
ss >> sRGB;
vstrImageFilenamesRGB.push_back(sRGB);
ss >> t;
ss >> sD;
vstrImageFilenamesD.push_back(sD);
}
}
}
================================================
FILE: Examples/Stereo/EuRoC.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# GPU Parameters
#--------------------------------------------------------------------------------------------
gpu.use_gpu: 1
gpu.is_jetson: 0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 435.2046959714599
Camera.fy: 435.2046959714599
Camera.cx: 367.4517211914062
Camera.cy: 252.2008514404297
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 752
Camera.height: 480
# Camera frames per second
Camera.fps: 20.0
# stereo baseline times fx
Camera.bf: 47.90639384423901
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35
#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 480
LEFT.width: 752
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [435.2046959714599, 0, 367.4517211914062, 0, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]
RIGHT.height: 480
RIGHT.width: 752
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
#30 30 20 15 10 for seq 01, 02, 03, 04, 05 respectively
ORBextractor.tile_h: 30
ORBextractor.tile_w: 30
ORBextractor.fixed_multi_scale_tile_size: 0
ORBextractor.apply_nms_ms: 0
ORBextractor.nms_ms_mode_gpu: 1
ORBextractor.scaleFactor: 1.2
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Firstly we impose th_FAST_MAX. If no corners are detected we impose a lower value th_FAST_MIN
# You can lower these values if your images have low contrast
ORBextractor.th_FAST_MIN: 7
ORBextractor.th_FAST_MAX: 20
ORBextractor.FAST_N_MIN: 9
ORBextractor.FAST_N_MAX: 14
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 40
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/MH01.txt
================================================
1403636579763555584
1403636579813555456
1403636579863555584
1403636579913555456
1403636579963555584
1403636580013555456
1403636580063555584
1403636580113555456
1403636580163555584
1403636580213555456
1403636580263555584
1403636580313555456
1403636580363555584
1403636580413555456
1403636580463555584
1403636580513555456
1403636580563555584
1403636580613555456
1403636580663555584
1403636580713555456
1403636580763555584
1403636580813555456
1403636580863555584
1403636580913555456
1403636580963555584
1403636581013555456
1403636581063555584
1403636581113555456
1403636581163555584
1403636581213555456
1403636581263555584
1403636581313555456
1403636581363555584
1403636581413555456
1403636581463555584
1403636581513555456
1403636581563555584
1403636581613555456
1403636581663555584
1403636581713555456
1403636581763555584
1403636581813555456
1403636581863555584
1403636581913555456
1403636581963555584
1403636582013555456
1403636582063555584
1403636582113555456
1403636582163555584
1403636582213555456
1403636582263555584
1403636582313555456
1403636582363555584
1403636582413555456
1403636582463555584
1403636582513555456
1403636582563555584
1403636582613555456
1403636582663555584
1403636582713555456
1403636582763555584
1403636582813555456
1403636582863555584
1403636582913555456
1403636582963555584
1403636583013555456
1403636583063555584
1403636583113555456
1403636583163555584
1403636583213555456
1403636583263555584
1403636583313555456
1403636583363555584
1403636583413555456
1403636583463555584
1403636583513555456
1403636583563555584
1403636583613555456
1403636583663555584
1403636583713555456
1403636583763555584
1403636583813555456
1403636583863555584
1403636583913555456
1403636583963555584
1403636584013555456
1403636584063555584
1403636584113555456
1403636584163555584
1403636584213555456
1403636584263555584
1403636584313555456
1403636584363555584
1403636584413555456
1403636584463555584
1403636584513555456
1403636584563555584
1403636584613555456
1403636584663555584
1403636584713555456
1403636584763555584
1403636584813555456
1403636584863555584
1403636584913555456
1403636584963555584
1403636585013555456
1403636585063555584
1403636585113555456
1403636585163555584
1403636585213555456
1403636585263555584
1403636585313555456
1403636585363555584
1403636585413555456
1403636585463555584
1403636585513555456
1403636585563555584
1403636585613555456
1403636585663555584
1403636585713555456
1403636585763555584
1403636585813555456
1403636585863555584
1403636585913555456
1403636585963555584
1403636586013555456
1403636586063555584
1403636586113555456
1403636586163555584
1403636586213555456
1403636586263555584
1403636586313555456
1403636586363555584
1403636586413555456
1403636586463555584
1403636586513555456
1403636586563555584
1403636586613555456
1403636586663555584
1403636586713555456
1403636586763555584
1403636586813555456
1403636586863555584
1403636586913555456
1403636586963555584
1403636587013555456
1403636587063555584
1403636587113555456
1403636587163555584
1403636587213555456
1403636587263555584
1403636587313555456
1403636587363555584
1403636587413555456
1403636587463555584
1403636587513555456
1403636587563555584
1403636587613555456
1403636587663555584
1403636587713555456
1403636587763555584
1403636587813555456
1403636587863555584
1403636587913555456
1403636587963555584
1403636588013555456
1403636588063555584
1403636588113555456
1403636588163555584
1403636588213555456
1403636588263555584
1403636588313555456
1403636588363555584
1403636588413555456
1403636588463555584
1403636588513555456
1403636588563555584
1403636588613555456
1403636588663555584
1403636588713555456
1403636588763555584
1403636588813555456
1403636588863555584
1403636588913555456
1403636588963555584
1403636589013555456
1403636589063555584
1403636589113555456
1403636589163555584
1403636589213555456
1403636589263555584
1403636589313555456
1403636589363555584
1403636589413555456
1403636589463555584
1403636589513555456
1403636589563555584
1403636589613555456
1403636589663555584
1403636589713555456
1403636589763555584
1403636589813555456
1403636589863555584
1403636589913555456
1403636589963555584
1403636590013555456
1403636590063555584
1403636590113555456
1403636590163555584
1403636590213555456
1403636590263555584
1403636590313555456
1403636590363555584
1403636590413555456
1403636590463555584
1403636590513555456
1403636590563555584
1403636590613555456
1403636590663555584
1403636590713555456
1403636590763555584
1403636590813555456
1403636590863555584
1403636590913555456
1403636590963555584
1403636591013555456
1403636591063555584
1403636591113555456
1403636591163555584
1403636591213555456
1403636591263555584
1403636591313555456
1403636591363555584
1403636591413555456
1403636591463555584
1403636591513555456
1403636591563555584
1403636591613555456
1403636591663555584
1403636591713555456
1403636591763555584
1403636591813555456
1403636591863555584
1403636591913555456
1403636591963555584
1403636592013555456
1403636592063555584
1403636592113555456
1403636592163555584
1403636592213555456
1403636592263555584
1403636592313555456
1403636592363555584
1403636592413555456
1403636592463555584
1403636592513555456
1403636592563555584
1403636592613555456
1403636592663555584
1403636592713555456
1403636592763555584
1403636592813555456
1403636592863555584
1403636592913555456
1403636592963555584
1403636593013555456
1403636593063555584
1403636593113555456
1403636593163555584
1403636593213555456
1403636593263555584
1403636593313555456
1403636593363555584
1403636593413555456
1403636593463555584
1403636593513555456
1403636593563555584
1403636593613555456
1403636593663555584
1403636593713555456
1403636593763555584
1403636593813555456
1403636593863555584
1403636593913555456
1403636593963555584
1403636594013555456
1403636594063555584
1403636594113555456
1403636594163555584
1403636594213555456
1403636594263555584
1403636594313555456
1403636594363555584
1403636594413555456
1403636594463555584
1403636594513555456
1403636594563555584
1403636594613555456
1403636594663555584
1403636594713555456
1403636594763555584
1403636594813555456
1403636594863555584
1403636594913555456
1403636594963555584
1403636595013555456
1403636595063555584
1403636595113555456
1403636595163555584
1403636595213555456
1403636595263555584
1403636595313555456
1403636595363555584
1403636595413555456
1403636595463555584
1403636595513555456
1403636595563555584
1403636595613555456
1403636595663555584
1403636595713555456
1403636595763555584
1403636595813555456
1403636595863555584
1403636595913555456
1403636595963555584
1403636596013555456
1403636596063555584
1403636596113555456
1403636596163555584
1403636596213555456
1403636596263555584
1403636596313555456
1403636596363555584
1403636596413555456
1403636596463555584
1403636596513555456
1403636596563555584
1403636596613555456
1403636596663555584
1403636596713555456
1403636596763555584
1403636596813555456
1403636596863555584
1403636596913555456
1403636596963555584
1403636597013555456
1403636597063555584
1403636597113555456
1403636597163555584
1403636597213555456
1403636597263555584
1403636597313555456
1403636597363555584
1403636597413555456
1403636597463555584
1403636597513555456
1403636597563555584
1403636597613555456
1403636597663555584
1403636597713555456
1403636597763555584
1403636597813555456
1403636597863555584
1403636597913555456
1403636597963555584
1403636598013555456
1403636598063555584
1403636598113555456
1403636598163555584
1403636598213555456
1403636598263555584
1403636598313555456
1403636598363555584
1403636598413555456
1403636598463555584
1403636598513555456
1403636598563555584
1403636598613555456
1403636598663555584
1403636598713555456
1403636598763555584
1403636598813555456
1403636598863555584
1403636598913555456
1403636598963555584
1403636599013555456
1403636599063555584
1403636599113555456
1403636599163555584
1403636599213555456
1403636599263555584
1403636599313555456
1403636599363555584
1403636599413555456
1403636599463555584
1403636599513555456
1403636599563555584
1403636599613555456
1403636599663555584
1403636599713555456
1403636599763555584
1403636599813555456
1403636599863555584
1403636599913555456
1403636599963555584
1403636600013555456
1403636600063555584
1403636600113555456
1403636600163555584
1403636600213555456
1403636600263555584
1403636600313555456
1403636600363555584
1403636600413555456
1403636600463555584
1403636600513555456
1403636600563555584
1403636600613555456
1403636600663555584
1403636600713555456
1403636600763555584
1403636600813555456
1403636600863555584
1403636600913555456
1403636600963555584
1403636601013555456
1403636601063555584
1403636601113555456
1403636601163555584
1403636601213555456
1403636601263555584
1403636601313555456
1403636601363555584
1403636601413555456
1403636601463555584
1403636601513555456
1403636601563555584
1403636601613555456
1403636601663555584
1403636601713555456
1403636601763555584
1403636601813555456
1403636601863555584
1403636601913555456
1403636601963555584
1403636602013555456
1403636602063555584
1403636602113555456
1403636602163555584
1403636602213555456
1403636602263555584
1403636602313555456
1403636602363555584
1403636602413555456
1403636602463555584
1403636602513555456
1403636602563555584
1403636602613555456
1403636602663555584
1403636602713555456
1403636602763555584
1403636602813555456
1403636602863555584
1403636602913555456
1403636602963555584
1403636603013555456
1403636603063555584
1403636603113555456
1403636603163555584
1403636603213555456
1403636603263555584
1403636603313555456
1403636603363555584
1403636603413555456
1403636603463555584
1403636603513555456
1403636603563555584
1403636603613555456
1403636603663555584
1403636603713555456
1403636603763555584
1403636603813555456
1403636603863555584
1403636603913555456
1403636603963555584
1403636604013555456
1403636604063555584
1403636604113555456
1403636604163555584
1403636604213555456
1403636604263555584
1403636604313555456
1403636604363555584
1403636604413555456
1403636604463555584
1403636604513555456
1403636604563555584
1403636604613555456
1403636604663555584
1403636604713555456
1403636604763555584
1403636604813555456
1403636604863555584
1403636604913555456
1403636604963555584
1403636605013555456
1403636605063555584
1403636605113555456
1403636605163555584
1403636605213555456
1403636605263555584
1403636605313555456
1403636605363555584
1403636605413555456
1403636605463555584
1403636605513555456
1403636605563555584
1403636605613555456
1403636605663555584
1403636605713555456
1403636605763555584
1403636605813555456
1403636605863555584
1403636605913555456
1403636605963555584
1403636606013555456
1403636606063555584
1403636606113555456
1403636606163555584
1403636606213555456
1403636606263555584
1403636606313555456
1403636606363555584
1403636606413555456
1403636606463555584
1403636606513555456
1403636606563555584
1403636606613555456
1403636606663555584
1403636606713555456
1403636606763555584
1403636606813555456
1403636606863555584
1403636606913555456
1403636606963555584
1403636607013555456
1403636607063555584
1403636607113555456
1403636607163555584
1403636607213555456
1403636607263555584
1403636607313555456
1403636607363555584
1403636607413555456
1403636607463555584
1403636607513555456
1403636607563555584
1403636607613555456
1403636607663555584
1403636607713555456
1403636607763555584
1403636607813555456
1403636607863555584
1403636607913555456
1403636607963555584
1403636608013555456
1403636608063555584
1403636608113555456
1403636608163555584
1403636608213555456
1403636608263555584
1403636608313555456
1403636608363555584
1403636608413555456
1403636608463555584
1403636608513555456
1403636608563555584
1403636608613555456
1403636608663555584
1403636608713555456
1403636608763555584
1403636608813555456
1403636608863555584
1403636608913555456
1403636608963555584
1403636609013555456
1403636609063555584
1403636609113555456
1403636609163555584
1403636609213555456
1403636609263555584
1403636609313555456
1403636609363555584
1403636609413555456
1403636609463555584
1403636609513555456
1403636609563555584
1403636609613555456
1403636609663555584
1403636609713555456
1403636609763555584
1403636609813555456
1403636609863555584
1403636609913555456
1403636609963555584
1403636610013555456
1403636610063555584
1403636610113555456
1403636610163555584
1403636610213555456
1403636610263555584
1403636610313555456
1403636610363555584
1403636610413555456
1403636610463555584
1403636610513555456
1403636610563555584
1403636610613555456
1403636610663555584
1403636610713555456
1403636610763555584
1403636610813555456
1403636610863555584
1403636610913555456
1403636610963555584
1403636611013555456
1403636611063555584
1403636611113555456
1403636611163555584
1403636611213555456
1403636611263555584
1403636611313555456
1403636611363555584
1403636611413555456
1403636611463555584
1403636611513555456
1403636611563555584
1403636611613555456
1403636611663555584
1403636611713555456
1403636611763555584
1403636611813555456
1403636611863555584
1403636611913555456
1403636611963555584
1403636612013555456
1403636612063555584
1403636612113555456
1403636612163555584
1403636612213555456
1403636612263555584
1403636612313555456
1403636612363555584
1403636612413555456
1403636612463555584
1403636612513555456
1403636612563555584
1403636612613555456
1403636612663555584
1403636612713555456
1403636612763555584
1403636612813555456
1403636612863555584
1403636612913555456
1403636612963555584
1403636613013555456
1403636613063555584
1403636613113555456
1403636613163555584
1403636613213555456
1403636613263555584
1403636613313555456
1403636613363555584
1403636613413555456
1403636613463555584
1403636613513555456
1403636613563555584
1403636613613555456
1403636613663555584
1403636613713555456
1403636613763555584
1403636613813555456
1403636613863555584
1403636613913555456
1403636613963555584
1403636614013555456
1403636614063555584
1403636614113555456
1403636614163555584
1403636614213555456
1403636614263555584
1403636614313555456
1403636614363555584
1403636614413555456
1403636614463555584
1403636614513555456
1403636614563555584
1403636614613555456
1403636614663555584
1403636614713555456
1403636614763555584
1403636614813555456
1403636614863555584
1403636614913555456
1403636614963555584
1403636615013555456
1403636615063555584
1403636615113555456
1403636615163555584
1403636615213555456
1403636615263555584
1403636615313555456
1403636615363555584
1403636615413555456
1403636615463555584
1403636615513555456
1403636615563555584
1403636615613555456
1403636615663555584
1403636615713555456
1403636615763555584
1403636615813555456
1403636615863555584
1403636615913555456
1403636615963555584
1403636616013555456
1403636616063555584
1403636616113555456
1403636616163555584
1403636616213555456
1403636616263555584
1403636616313555456
1403636616363555584
1403636616413555456
1403636616463555584
1403636616513555456
1403636616563555584
1403636616613555456
1403636616663555584
1403636616713555456
1403636616763555584
1403636616813555456
1403636616863555584
1403636616913555456
1403636616963555584
1403636617013555456
1403636617063555584
1403636617113555456
1403636617163555584
1403636617213555456
1403636617263555584
1403636617313555456
1403636617363555584
1403636617413555456
1403636617463555584
1403636617513555456
1403636617563555584
1403636617613555456
1403636617663555584
1403636617713555456
1403636617763555584
1403636617813555456
1403636617863555584
1403636617913555456
1403636617963555584
1403636618013555456
1403636618063555584
1403636618113555456
1403636618163555584
1403636618213555456
1403636618263555584
1403636618313555456
1403636618363555584
1403636618413555456
1403636618463555584
1403636618513555456
1403636618563555584
1403636618613555456
1403636618663555584
1403636618713555456
1403636618763555584
1403636618813555456
1403636618863555584
1403636618913555456
1403636618963555584
1403636619013555456
1403636619063555584
1403636619113555456
1403636619163555584
1403636619213555456
1403636619263555584
1403636619313555456
1403636619363555584
1403636619413555456
1403636619463555584
1403636619513555456
1403636619563555584
1403636619613555456
1403636619663555584
1403636619713555456
1403636619763555584
1403636619813555456
1403636619863555584
1403636619913555456
1403636619963555584
1403636620013555456
1403636620063555584
1403636620113555456
1403636620163555584
1403636620213555456
1403636620263555584
1403636620313555456
1403636620363555584
1403636620413555456
1403636620463555584
1403636620513555456
1403636620563555584
1403636620613555456
1403636620663555584
1403636620713555456
1403636620763555584
1403636620813555456
1403636620863555584
1403636620913555456
1403636620963555584
1403636621013555456
1403636621063555584
1403636621113555456
1403636621163555584
1403636621213555456
1403636621263555584
1403636621313555456
1403636621363555584
1403636621413555456
1403636621463555584
1403636621513555456
1403636621563555584
1403636621613555456
1403636621663555584
1403636621713555456
1403636621763555584
1403636621813555456
1403636621863555584
1403636621913555456
1403636621963555584
1403636622013555456
1403636622063555584
1403636622113555456
1403636622163555584
1403636622213555456
1403636622263555584
1403636622313555456
1403636622363555584
1403636622413555456
1403636622463555584
1403636622513555456
1403636622563555584
1403636622613555456
1403636622663555584
1403636622713555456
1403636622763555584
1403636622813555456
1403636622863555584
1403636622913555456
1403636622963555584
1403636623013555456
1403636623063555584
1403636623113555456
1403636623163555584
1403636623213555456
1403636623263555584
1403636623313555456
1403636623363555584
1403636623413555456
1403636623463555584
1403636623513555456
1403636623563555584
1403636623613555456
1403636623663555584
1403636623713555456
1403636623763555584
1403636623813555456
1403636623863555584
1403636623913555456
1403636623963555584
1403636624013555456
1403636624063555584
1403636624113555456
1403636624163555584
1403636624213555456
1403636624263555584
1403636624313555456
1403636624363555584
1403636624413555456
1403636624463555584
1403636624513555456
1403636624563555584
1403636624613555456
1403636624663555584
1403636624713555456
1403636624763555584
1403636624813555456
1403636624863555584
1403636624913555456
1403636624963555584
1403636625013555456
1403636625063555584
1403636625113555456
1403636625163555584
1403636625213555456
1403636625263555584
1403636625313555456
1403636625363555584
1403636625413555456
1403636625463555584
1403636625513555456
1403636625563555584
1403636625613555456
1403636625663555584
1403636625713555456
1403636625763555584
1403636625813555456
1403636625863555584
1403636625913555456
1403636625963555584
1403636626013555456
1403636626063555584
1403636626113555456
1403636626163555584
1403636626213555456
1403636626263555584
1403636626313555456
1403636626363555584
1403636626413555456
1403636626463555584
1403636626513555456
1403636626563555584
1403636626613555456
1403636626663555584
1403636626713555456
1403636626763555584
1403636626813555456
1403636626863555584
1403636626913555456
1403636626963555584
1403636627013555456
1403636627063555584
1403636627113555456
1403636627163555584
1403636627213555456
1403636627263555584
1403636627313555456
1403636627363555584
1403636627413555456
1403636627463555584
1403636627513555456
1403636627563555584
1403636627613555456
1403636627663555584
1403636627713555456
1403636627763555584
1403636627813555456
1403636627863555584
1403636627913555456
1403636627963555584
1403636628013555456
1403636628063555584
1403636628113555456
1403636628163555584
1403636628213555456
1403636628263555584
1403636628313555456
1403636628363555584
1403636628413555456
1403636628463555584
1403636628513555456
1403636628563555584
1403636628613555456
1403636628663555584
1403636628713555456
1403636628763555584
1403636628813555456
1403636628863555584
1403636628913555456
1403636628963555584
1403636629013555456
1403636629063555584
1403636629113555456
1403636629163555584
1403636629213555456
1403636629263555584
1403636629313555456
1403636629363555584
1403636629413555456
1403636629463555584
1403636629513555456
1403636629563555584
1403636629613555456
1403636629663555584
1403636629713555456
1403636629763555584
1403636629813555456
1403636629863555584
1403636629913555456
1403636629963555584
1403636630013555456
1403636630063555584
1403636630113555456
1403636630163555584
1403636630213555456
1403636630263555584
1403636630313555456
1403636630363555584
1403636630413555456
1403636630463555584
1403636630513555456
1403636630563555584
1403636630613555456
1403636630663555584
1403636630713555456
1403636630763555584
1403636630813555456
1403636630863555584
1403636630913555456
1403636630963555584
1403636631013555456
1403636631063555584
1403636631113555456
1403636631163555584
1403636631213555456
1403636631263555584
1403636631313555456
1403636631363555584
1403636631413555456
1403636631463555584
1403636631513555456
1403636631563555584
1403636631613555456
1403636631663555584
1403636631713555456
1403636631763555584
1403636631813555456
1403636631863555584
1403636631913555456
1403636631963555584
1403636632013555456
1403636632063555584
1403636632113555456
1403636632163555584
1403636632213555456
1403636632263555584
1403636632313555456
1403636632363555584
1403636632413555456
1403636632463555584
1403636632513555456
1403636632563555584
1403636632613555456
1403636632663555584
1403636632713555456
1403636632763555584
1403636632813555456
1403636632863555584
1403636632913555456
1403636632963555584
1403636633013555456
1403636633063555584
1403636633113555456
1403636633163555584
1403636633213555456
1403636633263555584
1403636633313555456
1403636633363555584
1403636633413555456
1403636633463555584
1403636633513555456
1403636633563555584
1403636633613555456
1403636633663555584
1403636633713555456
1403636633763555584
1403636633813555456
1403636633863555584
1403636633913555456
1403636633963555584
1403636634013555456
1403636634063555584
1403636634113555456
1403636634163555584
1403636634213555456
1403636634263555584
1403636634313555456
1403636634363555584
1403636634413555456
1403636634463555584
1403636634513555456
1403636634563555584
1403636634613555456
1403636634663555584
1403636634713555456
1403636634763555584
1403636634813555456
1403636634863555584
1403636634913555456
1403636634963555584
1403636635013555456
1403636635063555584
1403636635113555456
1403636635163555584
1403636635213555456
1403636635263555584
1403636635313555456
1403636635363555584
1403636635413555456
1403636635463555584
1403636635513555456
1403636635563555584
1403636635613555456
1403636635663555584
1403636635713555456
1403636635763555584
1403636635813555456
1403636635863555584
1403636635913555456
1403636635963555584
1403636636013555456
1403636636063555584
1403636636113555456
1403636636163555584
1403636636213555456
1403636636263555584
1403636636313555456
1403636636363555584
1403636636413555456
1403636636463555584
1403636636513555456
1403636636563555584
1403636636613555456
1403636636663555584
1403636636713555456
1403636636763555584
1403636636813555456
1403636636863555584
1403636636913555456
1403636636963555584
1403636637013555456
1403636637063555584
1403636637113555456
1403636637163555584
1403636637213555456
1403636637263555584
1403636637313555456
1403636637363555584
1403636637413555456
1403636637463555584
1403636637513555456
1403636637563555584
1403636637613555456
1403636637663555584
1403636637713555456
1403636637763555584
1403636637813555456
1403636637863555584
1403636637913555456
1403636637963555584
1403636638013555456
1403636638063555584
1403636638113555456
1403636638163555584
1403636638213555456
1403636638263555584
1403636638313555456
1403636638363555584
1403636638413555456
1403636638463555584
1403636638513555456
1403636638563555584
1403636638613555456
1403636638663555584
1403636638713555456
1403636638763555584
1403636638813555456
1403636638863555584
1403636638913555456
1403636638963555584
1403636639013555456
1403636639063555584
1403636639113555456
1403636639163555584
1403636639213555456
1403636639263555584
1403636639313555456
1403636639363555584
1403636639413555456
1403636639463555584
1403636639513555456
1403636639563555584
1403636639613555456
1403636639663555584
1403636639713555456
1403636639763555584
1403636639813555456
1403636639863555584
1403636639913555456
1403636639963555584
1403636640013555456
1403636640063555584
1403636640113555456
1403636640163555584
1403636640213555456
1403636640263555584
1403636640313555456
1403636640363555584
1403636640413555456
1403636640463555584
1403636640513555456
1403636640563555584
1403636640613555456
1403636640663555584
1403636640713555456
1403636640763555584
1403636640813555456
1403636640863555584
1403636640913555456
1403636640963555584
1403636641013555456
1403636641063555584
1403636641113555456
1403636641163555584
1403636641213555456
1403636641263555584
1403636641313555456
1403636641363555584
1403636641413555456
1403636641463555584
1403636641513555456
1403636641563555584
1403636641613555456
1403636641663555584
1403636641713555456
1403636641763555584
1403636641813555456
1403636641863555584
1403636641913555456
1403636641963555584
1403636642013555456
1403636642063555584
1403636642113555456
1403636642163555584
1403636642213555456
1403636642263555584
1403636642313555456
1403636642363555584
1403636642413555456
1403636642463555584
1403636642513555456
1403636642563555584
1403636642613555456
1403636642663555584
1403636642713555456
1403636642763555584
1403636642813555456
1403636642863555584
1403636642913555456
1403636642963555584
1403636643013555456
1403636643063555584
1403636643113555456
1403636643163555584
1403636643213555456
1403636643263555584
1403636643313555456
1403636643363555584
1403636643413555456
1403636643463555584
1403636643513555456
1403636643563555584
1403636643613555456
1403636643663555584
1403636643713555456
1403636643763555584
1403636643813555456
1403636643863555584
1403636643913555456
1403636643963555584
1403636644013555456
1403636644063555584
1403636644113555456
1403636644163555584
1403636644213555456
1403636644263555584
1403636644313555456
1403636644363555584
1403636644413555456
1403636644463555584
1403636644513555456
1403636644563555584
1403636644613555456
1403636644663555584
1403636644713555456
1403636644763555584
1403636644813555456
1403636644863555584
1403636644913555456
1403636644963555584
1403636645013555456
1403636645063555584
1403636645113555456
1403636645163555584
1403636645213555456
1403636645263555584
1403636645313555456
1403636645363555584
1403636645413555456
1403636645463555584
1403636645513555456
1403636645563555584
1403636645613555456
1403636645663555584
1403636645713555456
1403636645763555584
1403636645813555456
1403636645863555584
1403636645913555456
1403636645963555584
1403636646013555456
1403636646063555584
1403636646113555456
1403636646163555584
1403636646213555456
1403636646263555584
1403636646313555456
1403636646363555584
1403636646413555456
1403636646463555584
1403636646513555456
1403636646563555584
1403636646613555456
1403636646663555584
1403636646713555456
1403636646763555584
1403636646813555456
1403636646863555584
1403636646913555456
1403636646963555584
1403636647013555456
1403636647063555584
1403636647113555456
1403636647163555584
1403636647213555456
1403636647263555584
1403636647313555456
1403636647363555584
1403636647413555456
1403636647463555584
1403636647513555456
1403636647563555584
1403636647613555456
1403636647663555584
1403636647713555456
1403636647763555584
1403636647813555456
1403636647863555584
1403636647913555456
1403636647963555584
1403636648013555456
1403636648063555584
1403636648113555456
1403636648163555584
1403636648213555456
1403636648263555584
1403636648313555456
1403636648363555584
1403636648413555456
1403636648463555584
1403636648513555456
1403636648563555584
1403636648613555456
1403636648663555584
1403636648713555456
1403636648763555584
1403636648813555456
1403636648863555584
1403636648913555456
1403636648963555584
1403636649013555456
1403636649063555584
1403636649113555456
1403636649163555584
1403636649213555456
1403636649263555584
1403636649313555456
1403636649363555584
1403636649413555456
1403636649463555584
1403636649513555456
1403636649563555584
1403636649613555456
1403636649663555584
1403636649713555456
1403636649763555584
1403636649813555456
1403636649863555584
1403636649913555456
1403636649963555584
1403636650013555456
1403636650063555584
1403636650113555456
1403636650163555584
1403636650213555456
1403636650263555584
1403636650313555456
1403636650363555584
1403636650413555456
1403636650463555584
1403636650513555456
1403636650563555584
1403636650613555456
1403636650663555584
1403636650713555456
1403636650763555584
1403636650813555456
1403636650863555584
1403636650913555456
1403636650963555584
1403636651013555456
1403636651063555584
1403636651113555456
1403636651163555584
1403636651213555456
1403636651263555584
1403636651313555456
1403636651363555584
1403636651413555456
1403636651463555584
1403636651513555456
1403636651563555584
1403636651613555456
1403636651663555584
1403636651713555456
1403636651763555584
1403636651813555456
1403636651863555584
1403636651913555456
1403636651963555584
1403636652013555456
1403636652063555584
1403636652113555456
1403636652163555584
1403636652213555456
1403636652263555584
1403636652313555456
1403636652363555584
1403636652413555456
1403636652463555584
1403636652513555456
1403636652563555584
1403636652613555456
1403636652663555584
1403636652713555456
1403636652763555584
1403636652813555456
1403636652863555584
1403636652913555456
1403636652963555584
1403636653013555456
1403636653063555584
1403636653113555456
1403636653163555584
1403636653213555456
1403636653263555584
1403636653313555456
1403636653363555584
1403636653413555456
1403636653463555584
1403636653513555456
1403636653563555584
1403636653613555456
1403636653663555584
1403636653713555456
1403636653763555584
1403636653813555456
1403636653863555584
1403636653913555456
1403636653963555584
1403636654013555456
1403636654063555584
1403636654113555456
1403636654163555584
1403636654213555456
1403636654263555584
1403636654313555456
1403636654363555584
1403636654413555456
1403636654463555584
1403636654513555456
1403636654563555584
1403636654613555456
1403636654663555584
1403636654713555456
1403636654763555584
1403636654813555456
1403636654863555584
1403636654913555456
1403636654963555584
1403636655013555456
1403636655063555584
1403636655113555456
1403636655163555584
1403636655213555456
1403636655263555584
1403636655313555456
1403636655363555584
1403636655413555456
1403636655463555584
1403636655513555456
1403636655563555584
1403636655613555456
1403636655663555584
1403636655713555456
1403636655763555584
1403636655813555456
1403636655863555584
1403636655913555456
1403636655963555584
1403636656013555456
1403636656063555584
1403636656113555456
1403636656163555584
1403636656213555456
1403636656263555584
1403636656313555456
1403636656363555584
1403636656413555456
1403636656463555584
1403636656513555456
1403636656563555584
1403636656613555456
1403636656663555584
1403636656713555456
1403636656763555584
1403636656813555456
1403636656863555584
1403636656913555456
1403636656963555584
1403636657013555456
1403636657063555584
1403636657113555456
1403636657163555584
1403636657213555456
1403636657263555584
1403636657313555456
1403636657363555584
1403636657413555456
1403636657463555584
1403636657513555456
1403636657563555584
1403636657613555456
1403636657663555584
1403636657713555456
1403636657763555584
1403636657813555456
1403636657863555584
1403636657913555456
1403636657963555584
1403636658013555456
1403636658063555584
1403636658113555456
1403636658163555584
1403636658213555456
1403636658263555584
1403636658313555456
1403636658363555584
1403636658413555456
1403636658463555584
1403636658513555456
1403636658563555584
1403636658613555456
1403636658663555584
1403636658713555456
1403636658763555584
1403636658813555456
1403636658863555584
1403636658913555456
1403636658963555584
1403636659013555456
1403636659063555584
1403636659113555456
1403636659163555584
1403636659213555456
1403636659263555584
1403636659313555456
1403636659363555584
1403636659413555456
1403636659463555584
1403636659513555456
1403636659563555584
1403636659613555456
1403636659663555584
1403636659713555456
1403636659763555584
1403636659813555456
1403636659863555584
1403636659913555456
1403636659963555584
1403636660013555456
1403636660063555584
1403636660113555456
1403636660163555584
1403636660213555456
1403636660263555584
1403636660313555456
1403636660363555584
1403636660413555456
1403636660463555584
1403636660513555456
1403636660563555584
1403636660613555456
1403636660663555584
1403636660713555456
1403636660763555584
1403636660813555456
1403636660863555584
1403636660913555456
1403636660963555584
1403636661013555456
1403636661063555584
1403636661113555456
1403636661163555584
1403636661213555456
1403636661263555584
1403636661313555456
1403636661363555584
1403636661413555456
1403636661463555584
1403636661513555456
1403636661563555584
1403636661613555456
1403636661663555584
1403636661713555456
1403636661763555584
1403636661813555456
1403636661863555584
1403636661913555456
1403636661963555584
1403636662013555456
1403636662063555584
1403636662113555456
1403636662163555584
1403636662213555456
1403636662263555584
1403636662313555456
1403636662363555584
1403636662413555456
1403636662463555584
1403636662513555456
1403636662563555584
1403636662613555456
1403636662663555584
1403636662713555456
1403636662763555584
1403636662813555456
1403636662863555584
1403636662913555456
1403636662963555584
1403636663013555456
1403636663063555584
1403636663113555456
1403636663163555584
1403636663213555456
1403636663263555584
1403636663313555456
1403636663363555584
1403636663413555456
1403636663463555584
1403636663513555456
1403636663563555584
1403636663613555456
1403636663663555584
1403636663713555456
1403636663763555584
1403636663813555456
1403636663863555584
1403636663913555456
1403636663963555584
1403636664013555456
1403636664063555584
1403636664113555456
1403636664163555584
1403636664213555456
1403636664263555584
1403636664313555456
1403636664363555584
1403636664413555456
1403636664463555584
1403636664513555456
1403636664563555584
1403636664613555456
1403636664663555584
1403636664713555456
1403636664763555584
1403636664813555456
1403636664863555584
1403636664913555456
1403636664963555584
1403636665013555456
1403636665063555584
1403636665113555456
1403636665163555584
1403636665213555456
1403636665263555584
1403636665313555456
1403636665363555584
1403636665413555456
1403636665463555584
1403636665513555456
1403636665563555584
1403636665613555456
1403636665663555584
1403636665713555456
1403636665763555584
1403636665813555456
1403636665863555584
1403636665913555456
1403636665963555584
1403636666013555456
1403636666063555584
1403636666113555456
1403636666163555584
1403636666213555456
1403636666263555584
1403636666313555456
1403636666363555584
1403636666413555456
1403636666463555584
1403636666513555456
1403636666563555584
1403636666613555456
1403636666663555584
1403636666713555456
1403636666763555584
1403636666813555456
1403636666863555584
1403636666913555456
1403636666963555584
1403636667013555456
1403636667063555584
1403636667113555456
1403636667163555584
1403636667213555456
1403636667263555584
1403636667313555456
1403636667363555584
1403636667413555456
1403636667463555584
1403636667513555456
1403636667563555584
1403636667613555456
1403636667663555584
1403636667713555456
1403636667763555584
1403636667813555456
1403636667863555584
1403636667913555456
1403636667963555584
1403636668013555456
1403636668063555584
1403636668113555456
1403636668163555584
1403636668213555456
1403636668263555584
1403636668313555456
1403636668363555584
1403636668413555456
1403636668463555584
1403636668513555456
1403636668563555584
1403636668613555456
1403636668663555584
1403636668713555456
1403636668763555584
1403636668813555456
1403636668863555584
1403636668913555456
1403636668963555584
1403636669013555456
1403636669063555584
1403636669113555456
1403636669163555584
1403636669213555456
1403636669263555584
1403636669313555456
1403636669363555584
1403636669413555456
1403636669463555584
1403636669513555456
1403636669563555584
1403636669613555456
1403636669663555584
1403636669713555456
1403636669763555584
1403636669813555456
1403636669863555584
1403636669913555456
1403636669963555584
1403636670013555456
1403636670063555584
1403636670113555456
1403636670163555584
1403636670213555456
1403636670263555584
1403636670313555456
1403636670363555584
1403636670413555456
1403636670463555584
1403636670513555456
1403636670563555584
1403636670613555456
1403636670663555584
1403636670713555456
1403636670763555584
1403636670813555456
1403636670863555584
1403636670913555456
1403636670963555584
1403636671013555456
1403636671063555584
1403636671113555456
1403636671163555584
1403636671213555456
1403636671263555584
1403636671313555456
1403636671363555584
1403636671413555456
1403636671463555584
1403636671513555456
1403636671563555584
1403636671613555456
1403636671663555584
1403636671713555456
1403636671763555584
1403636671813555456
1403636671863555584
1403636671913555456
1403636671963555584
1403636672013555456
1403636672063555584
1403636672113555456
1403636672163555584
1403636672213555456
1403636672263555584
1403636672313555456
1403636672363555584
1403636672413555456
1403636672463555584
1403636672513555456
1403636672563555584
1403636672613555456
1403636672663555584
1403636672713555456
1403636672763555584
1403636672813555456
1403636672863555584
1403636672913555456
1403636672963555584
1403636673013555456
1403636673063555584
1403636673113555456
1403636673163555584
1403636673213555456
1403636673263555584
1403636673313555456
1403636673363555584
1403636673413555456
1403636673463555584
1403636673513555456
1403636673563555584
1403636673613555456
1403636673663555584
1403636673713555456
1403636673763555584
1403636673813555456
1403636673863555584
1403636673913555456
1403636673963555584
1403636674013555456
1403636674063555584
1403636674113555456
1403636674163555584
1403636674213555456
1403636674263555584
1403636674313555456
1403636674363555584
1403636674413555456
1403636674463555584
1403636674513555456
1403636674563555584
1403636674613555456
1403636674663555584
1403636674713555456
1403636674763555584
1403636674813555456
1403636674863555584
1403636674913555456
1403636674963555584
1403636675013555456
1403636675063555584
1403636675113555456
1403636675163555584
1403636675213555456
1403636675263555584
1403636675313555456
1403636675363555584
1403636675413555456
1403636675463555584
1403636675513555456
1403636675563555584
1403636675613555456
1403636675663555584
1403636675713555456
1403636675763555584
1403636675813555456
1403636675863555584
1403636675913555456
1403636675963555584
1403636676013555456
1403636676063555584
1403636676113555456
1403636676163555584
1403636676213555456
1403636676263555584
1403636676313555456
1403636676363555584
1403636676413555456
1403636676463555584
1403636676513555456
1403636676563555584
1403636676613555456
1403636676663555584
1403636676713555456
1403636676763555584
1403636676813555456
1403636676863555584
1403636676913555456
1403636676963555584
1403636677013555456
1403636677063555584
1403636677113555456
1403636677163555584
1403636677213555456
1403636677263555584
1403636677313555456
1403636677363555584
1403636677413555456
1403636677463555584
1403636677513555456
1403636677563555584
1403636677613555456
1403636677663555584
1403636677713555456
1403636677763555584
1403636677813555456
1403636677863555584
1403636677913555456
1403636677963555584
1403636678013555456
1403636678063555584
1403636678113555456
1403636678163555584
1403636678213555456
1403636678263555584
1403636678313555456
1403636678363555584
1403636678413555456
1403636678463555584
1403636678513555456
1403636678563555584
1403636678613555456
1403636678663555584
1403636678713555456
1403636678763555584
1403636678813555456
1403636678863555584
1403636678913555456
1403636678963555584
1403636679013555456
1403636679063555584
1403636679113555456
1403636679163555584
1403636679213555456
1403636679263555584
1403636679313555456
1403636679363555584
1403636679413555456
1403636679463555584
1403636679513555456
1403636679563555584
1403636679613555456
1403636679663555584
1403636679713555456
1403636679763555584
1403636679813555456
1403636679863555584
1403636679913555456
1403636679963555584
1403636680013555456
1403636680063555584
1403636680113555456
1403636680163555584
1403636680213555456
1403636680263555584
1403636680313555456
1403636680363555584
1403636680413555456
1403636680463555584
1403636680513555456
1403636680563555584
1403636680613555456
1403636680663555584
1403636680713555456
1403636680763555584
1403636680813555456
1403636680863555584
1403636680913555456
1403636680963555584
1403636681013555456
1403636681063555584
1403636681113555456
1403636681163555584
1403636681213555456
1403636681263555584
1403636681313555456
1403636681363555584
1403636681413555456
1403636681463555584
1403636681513555456
1403636681563555584
1403636681613555456
1403636681663555584
1403636681713555456
1403636681763555584
1403636681813555456
1403636681863555584
1403636681913555456
1403636681963555584
1403636682013555456
1403636682063555584
1403636682113555456
1403636682163555584
1403636682213555456
1403636682263555584
1403636682313555456
1403636682363555584
1403636682413555456
1403636682463555584
1403636682513555456
1403636682563555584
1403636682613555456
1403636682663555584
1403636682713555456
1403636682763555584
1403636682813555456
1403636682863555584
1403636682913555456
1403636682963555584
1403636683013555456
1403636683063555584
1403636683113555456
1403636683163555584
1403636683213555456
1403636683263555584
1403636683313555456
1403636683363555584
1403636683413555456
1403636683463555584
1403636683513555456
1403636683563555584
1403636683613555456
1403636683663555584
1403636683713555456
1403636683763555584
1403636683813555456
1403636683863555584
1403636683913555456
1403636683963555584
1403636684013555456
1403636684063555584
1403636684113555456
1403636684163555584
1403636684213555456
1403636684263555584
1403636684313555456
1403636684363555584
1403636684413555456
1403636684463555584
1403636684513555456
1403636684563555584
1403636684613555456
1403636684663555584
1403636684713555456
1403636684763555584
1403636684813555456
1403636684863555584
1403636684913555456
1403636684963555584
1403636685013555456
1403636685063555584
1403636685113555456
1403636685163555584
1403636685213555456
1403636685263555584
1403636685313555456
1403636685363555584
1403636685413555456
1403636685463555584
1403636685513555456
1403636685563555584
1403636685613555456
1403636685663555584
1403636685713555456
1403636685763555584
1403636685813555456
1403636685863555584
1403636685913555456
1403636685963555584
1403636686013555456
1403636686063555584
1403636686113555456
1403636686163555584
1403636686213555456
1403636686263555584
1403636686313555456
1403636686363555584
1403636686413555456
1403636686463555584
1403636686513555456
1403636686563555584
1403636686613555456
1403636686663555584
1403636686713555456
1403636686763555584
1403636686813555456
1403636686863555584
1403636686913555456
1403636686963555584
1403636687013555456
1403636687063555584
1403636687113555456
1403636687163555584
1403636687213555456
1403636687263555584
1403636687313555456
1403636687363555584
1403636687413555456
1403636687463555584
1403636687513555456
1403636687563555584
1403636687613555456
1403636687663555584
1403636687713555456
1403636687763555584
1403636687813555456
1403636687863555584
1403636687913555456
1403636687963555584
1403636688013555456
1403636688063555584
1403636688113555456
1403636688163555584
1403636688213555456
1403636688263555584
1403636688313555456
1403636688363555584
1403636688413555456
1403636688463555584
1403636688513555456
1403636688563555584
1403636688613555456
1403636688663555584
1403636688713555456
1403636688763555584
1403636688813555456
1403636688863555584
1403636688913555456
1403636688963555584
1403636689013555456
1403636689063555584
1403636689113555456
1403636689163555584
1403636689213555456
1403636689263555584
1403636689313555456
1403636689363555584
1403636689413555456
1403636689463555584
1403636689513555456
1403636689563555584
1403636689613555456
1403636689663555584
1403636689713555456
1403636689763555584
1403636689813555456
1403636689863555584
1403636689913555456
1403636689963555584
1403636690013555456
1403636690063555584
1403636690113555456
1403636690163555584
1403636690213555456
1403636690263555584
1403636690313555456
1403636690363555584
1403636690413555456
1403636690463555584
1403636690513555456
1403636690563555584
1403636690613555456
1403636690663555584
1403636690713555456
1403636690763555584
1403636690813555456
1403636690863555584
1403636690913555456
1403636690963555584
1403636691013555456
1403636691063555584
1403636691113555456
1403636691163555584
1403636691213555456
1403636691263555584
1403636691313555456
1403636691363555584
1403636691413555456
1403636691463555584
1403636691513555456
1403636691563555584
1403636691613555456
1403636691663555584
1403636691713555456
1403636691763555584
1403636691813555456
1403636691863555584
1403636691913555456
1403636691963555584
1403636692013555456
1403636692063555584
1403636692113555456
1403636692163555584
1403636692213555456
1403636692263555584
1403636692313555456
1403636692363555584
1403636692413555456
1403636692463555584
1403636692513555456
1403636692563555584
1403636692613555456
1403636692663555584
1403636692713555456
1403636692763555584
1403636692813555456
1403636692863555584
1403636692913555456
1403636692963555584
1403636693013555456
1403636693063555584
1403636693113555456
1403636693163555584
1403636693213555456
1403636693263555584
1403636693313555456
1403636693363555584
1403636693413555456
1403636693463555584
1403636693513555456
1403636693563555584
1403636693613555456
1403636693663555584
1403636693713555456
1403636693763555584
1403636693813555456
1403636693863555584
1403636693913555456
1403636693963555584
1403636694013555456
1403636694063555584
1403636694113555456
1403636694163555584
1403636694213555456
1403636694263555584
1403636694313555456
1403636694363555584
1403636694413555456
1403636694463555584
1403636694513555456
1403636694563555584
1403636694613555456
1403636694663555584
1403636694713555456
1403636694763555584
1403636694813555456
1403636694863555584
1403636694913555456
1403636694963555584
1403636695013555456
1403636695063555584
1403636695113555456
1403636695163555584
1403636695213555456
1403636695263555584
1403636695313555456
1403636695363555584
1403636695413555456
1403636695463555584
1403636695513555456
1403636695563555584
1403636695613555456
1403636695663555584
1403636695713555456
1403636695763555584
1403636695813555456
1403636695863555584
1403636695913555456
1403636695963555584
1403636696013555456
1403636696063555584
1403636696113555456
1403636696163555584
1403636696213555456
1403636696263555584
1403636696313555456
1403636696363555584
1403636696413555456
1403636696463555584
1403636696513555456
1403636696563555584
1403636696613555456
1403636696663555584
1403636696713555456
1403636696763555584
1403636696813555456
1403636696863555584
1403636696913555456
1403636696963555584
1403636697013555456
1403636697063555584
1403636697113555456
1403636697163555584
1403636697213555456
1403636697263555584
1403636697313555456
1403636697363555584
1403636697413555456
1403636697463555584
1403636697513555456
1403636697563555584
1403636697613555456
1403636697663555584
1403636697713555456
1403636697763555584
1403636697813555456
1403636697863555584
1403636697913555456
1403636697963555584
1403636698013555456
1403636698063555584
1403636698113555456
1403636698163555584
1403636698213555456
1403636698263555584
1403636698313555456
1403636698363555584
1403636698413555456
1403636698463555584
1403636698513555456
1403636698563555584
1403636698613555456
1403636698663555584
1403636698713555456
1403636698763555584
1403636698813555456
1403636698863555584
1403636698913555456
1403636698963555584
1403636699013555456
1403636699063555584
1403636699113555456
1403636699163555584
1403636699213555456
1403636699263555584
1403636699313555456
1403636699363555584
1403636699413555456
1403636699463555584
1403636699513555456
1403636699563555584
1403636699613555456
1403636699663555584
1403636699713555456
1403636699763555584
1403636699813555456
1403636699863555584
1403636699913555456
1403636699963555584
1403636700013555456
1403636700063555584
1403636700113555456
1403636700163555584
1403636700213555456
1403636700263555584
1403636700313555456
1403636700363555584
1403636700413555456
1403636700463555584
1403636700513555456
1403636700563555584
1403636700613555456
1403636700663555584
1403636700713555456
1403636700763555584
1403636700813555456
1403636700863555584
1403636700913555456
1403636700963555584
1403636701013555456
1403636701063555584
1403636701113555456
1403636701163555584
1403636701213555456
1403636701263555584
1403636701313555456
1403636701363555584
1403636701413555456
1403636701463555584
1403636701513555456
1403636701563555584
1403636701613555456
1403636701663555584
1403636701713555456
1403636701763555584
1403636701813555456
1403636701863555584
1403636701913555456
1403636701963555584
1403636702013555456
1403636702063555584
1403636702113555456
1403636702163555584
1403636702213555456
1403636702263555584
1403636702313555456
1403636702363555584
1403636702413555456
1403636702463555584
1403636702513555456
1403636702563555584
1403636702613555456
1403636702663555584
1403636702713555456
1403636702763555584
1403636702813555456
1403636702863555584
1403636702913555456
1403636702963555584
1403636703013555456
1403636703063555584
1403636703113555456
1403636703163555584
1403636703213555456
1403636703263555584
1403636703313555456
1403636703363555584
1403636703413555456
1403636703463555584
1403636703513555456
1403636703563555584
1403636703613555456
1403636703663555584
1403636703713555456
1403636703763555584
1403636703813555456
1403636703863555584
1403636703913555456
1403636703963555584
1403636704013555456
1403636704063555584
1403636704113555456
1403636704163555584
1403636704213555456
1403636704263555584
1403636704313555456
1403636704363555584
1403636704413555456
1403636704463555584
1403636704513555456
1403636704563555584
1403636704613555456
1403636704663555584
1403636704713555456
1403636704763555584
1403636704813555456
1403636704863555584
1403636704913555456
1403636704963555584
1403636705013555456
1403636705063555584
1403636705113555456
1403636705163555584
1403636705213555456
1403636705263555584
1403636705313555456
1403636705363555584
1403636705413555456
1403636705463555584
1403636705513555456
1403636705563555584
1403636705613555456
1403636705663555584
1403636705713555456
1403636705763555584
1403636705813555456
1403636705863555584
1403636705913555456
1403636705963555584
1403636706013555456
1403636706063555584
1403636706113555456
1403636706163555584
1403636706213555456
1403636706263555584
1403636706313555456
1403636706363555584
1403636706413555456
1403636706463555584
1403636706513555456
1403636706563555584
1403636706613555456
1403636706663555584
1403636706713555456
1403636706763555584
1403636706813555456
1403636706863555584
1403636706913555456
1403636706963555584
1403636707013555456
1403636707063555584
1403636707113555456
1403636707163555584
1403636707213555456
1403636707263555584
1403636707313555456
1403636707363555584
1403636707413555456
1403636707463555584
1403636707513555456
1403636707563555584
1403636707613555456
1403636707663555584
1403636707713555456
1403636707763555584
1403636707813555456
1403636707863555584
1403636707913555456
1403636707963555584
1403636708013555456
1403636708063555584
1403636708113555456
1403636708163555584
1403636708213555456
1403636708263555584
1403636708313555456
1403636708363555584
1403636708413555456
1403636708463555584
1403636708513555456
1403636708563555584
1403636708613555456
1403636708663555584
1403636708713555456
1403636708763555584
1403636708813555456
1403636708863555584
1403636708913555456
1403636708963555584
1403636709013555456
1403636709063555584
1403636709113555456
1403636709163555584
1403636709213555456
1403636709263555584
1403636709313555456
1403636709363555584
1403636709413555456
1403636709463555584
1403636709513555456
1403636709563555584
1403636709613555456
1403636709663555584
1403636709713555456
1403636709763555584
1403636709813555456
1403636709863555584
1403636709913555456
1403636709963555584
1403636710013555456
1403636710063555584
1403636710113555456
1403636710163555584
1403636710213555456
1403636710263555584
1403636710313555456
1403636710363555584
1403636710413555456
1403636710463555584
1403636710513555456
1403636710563555584
1403636710613555456
1403636710663555584
1403636710713555456
1403636710763555584
1403636710813555456
1403636710863555584
1403636710913555456
1403636710963555584
1403636711013555456
1403636711063555584
1403636711113555456
1403636711163555584
1403636711213555456
1403636711263555584
1403636711313555456
1403636711363555584
1403636711413555456
1403636711463555584
1403636711513555456
1403636711563555584
1403636711613555456
1403636711663555584
1403636711713555456
1403636711763555584
1403636711813555456
1403636711863555584
1403636711913555456
1403636711963555584
1403636712013555456
1403636712063555584
1403636712113555456
1403636712163555584
1403636712213555456
1403636712263555584
1403636712313555456
1403636712363555584
1403636712413555456
1403636712463555584
1403636712513555456
1403636712563555584
1403636712613555456
1403636712663555584
1403636712713555456
1403636712763555584
1403636712813555456
1403636712863555584
1403636712913555456
1403636712963555584
1403636713013555456
1403636713063555584
1403636713113555456
1403636713163555584
1403636713213555456
1403636713263555584
1403636713313555456
1403636713363555584
1403636713413555456
1403636713463555584
1403636713513555456
1403636713563555584
1403636713613555456
1403636713663555584
1403636713713555456
1403636713763555584
1403636713813555456
1403636713863555584
1403636713913555456
1403636713963555584
1403636714013555456
1403636714063555584
1403636714113555456
1403636714163555584
1403636714213555456
1403636714263555584
1403636714313555456
1403636714363555584
1403636714413555456
1403636714463555584
1403636714513555456
1403636714563555584
1403636714613555456
1403636714663555584
1403636714713555456
1403636714763555584
1403636714813555456
1403636714863555584
1403636714913555456
1403636714963555584
1403636715013555456
1403636715063555584
1403636715113555456
1403636715163555584
1403636715213555456
1403636715263555584
1403636715313555456
1403636715363555584
1403636715413555456
1403636715463555584
1403636715513555456
1403636715563555584
1403636715613555456
1403636715663555584
1403636715713555456
1403636715763555584
1403636715813555456
1403636715863555584
1403636715913555456
1403636715963555584
1403636716013555456
1403636716063555584
1403636716113555456
1403636716163555584
1403636716213555456
1403636716263555584
1403636716313555456
1403636716363555584
1403636716413555456
1403636716463555584
1403636716513555456
1403636716563555584
1403636716613555456
1403636716663555584
1403636716713555456
1403636716763555584
1403636716813555456
1403636716863555584
1403636716913555456
1403636716963555584
1403636717013555456
1403636717063555584
1403636717113555456
1403636717163555584
1403636717213555456
1403636717263555584
1403636717313555456
1403636717363555584
1403636717413555456
1403636717463555584
1403636717513555456
1403636717563555584
1403636717613555456
1403636717663555584
1403636717713555456
1403636717763555584
1403636717813555456
1403636717863555584
1403636717913555456
1403636717963555584
1403636718013555456
1403636718063555584
1403636718113555456
1403636718163555584
1403636718213555456
1403636718263555584
1403636718313555456
1403636718363555584
1403636718413555456
1403636718463555584
1403636718513555456
1403636718563555584
1403636718613555456
1403636718663555584
1403636718713555456
1403636718763555584
1403636718813555456
1403636718863555584
1403636718913555456
1403636718963555584
1403636719013555456
1403636719063555584
1403636719113555456
1403636719163555584
1403636719213555456
1403636719263555584
1403636719313555456
1403636719363555584
1403636719413555456
1403636719463555584
1403636719513555456
1403636719563555584
1403636719613555456
1403636719663555584
1403636719713555456
1403636719763555584
1403636719813555456
1403636719863555584
1403636719913555456
1403636719963555584
1403636720013555456
1403636720063555584
1403636720113555456
1403636720163555584
1403636720213555456
1403636720263555584
1403636720313555456
1403636720363555584
1403636720413555456
1403636720463555584
1403636720513555456
1403636720563555584
1403636720613555456
1403636720663555584
1403636720713555456
1403636720763555584
1403636720813555456
1403636720863555584
1403636720913555456
1403636720963555584
1403636721013555456
1403636721063555584
1403636721113555456
1403636721163555584
1403636721213555456
1403636721263555584
1403636721313555456
1403636721363555584
1403636721413555456
1403636721463555584
1403636721513555456
1403636721563555584
1403636721613555456
1403636721663555584
1403636721713555456
1403636721763555584
1403636721813555456
1403636721863555584
1403636721913555456
1403636721963555584
1403636722013555456
1403636722063555584
1403636722113555456
1403636722163555584
1403636722213555456
1403636722263555584
1403636722313555456
1403636722363555584
1403636722413555456
1403636722463555584
1403636722513555456
1403636722563555584
1403636722613555456
1403636722663555584
1403636722713555456
1403636722763555584
1403636722813555456
1403636722863555584
1403636722913555456
1403636722963555584
1403636723013555456
1403636723063555584
1403636723113555456
1403636723163555584
1403636723213555456
1403636723263555584
1403636723313555456
1403636723363555584
1403636723413555456
1403636723463555584
1403636723513555456
1403636723563555584
1403636723613555456
1403636723663555584
1403636723713555456
1403636723763555584
1403636723813555456
1403636723863555584
1403636723913555456
1403636723963555584
1403636724013555456
1403636724063555584
1403636724113555456
1403636724163555584
1403636724213555456
1403636724263555584
1403636724313555456
1403636724363555584
1403636724413555456
1403636724463555584
1403636724513555456
1403636724563555584
1403636724613555456
1403636724663555584
1403636724713555456
1403636724763555584
1403636724813555456
1403636724863555584
1403636724913555456
1403636724963555584
1403636725013555456
1403636725063555584
1403636725113555456
1403636725163555584
1403636725213555456
1403636725263555584
1403636725313555456
1403636725363555584
1403636725413555456
1403636725463555584
1403636725513555456
1403636725563555584
1403636725613555456
1403636725663555584
1403636725713555456
1403636725763555584
1403636725813555456
1403636725863555584
1403636725913555456
1403636725963555584
1403636726013555456
1403636726063555584
1403636726113555456
1403636726163555584
1403636726213555456
1403636726263555584
1403636726313555456
1403636726363555584
1403636726413555456
1403636726463555584
1403636726513555456
1403636726563555584
1403636726613555456
1403636726663555584
1403636726713555456
1403636726763555584
1403636726813555456
1403636726863555584
1403636726913555456
1403636726963555584
1403636727013555456
1403636727063555584
1403636727113555456
1403636727163555584
1403636727213555456
1403636727263555584
1403636727313555456
1403636727363555584
1403636727413555456
1403636727463555584
1403636727513555456
1403636727563555584
1403636727613555456
1403636727663555584
1403636727713555456
1403636727763555584
1403636727813555456
1403636727863555584
1403636727913555456
1403636727963555584
1403636728013555456
1403636728063555584
1403636728113555456
1403636728163555584
1403636728213555456
1403636728263555584
1403636728313555456
1403636728363555584
1403636728413555456
1403636728463555584
1403636728513555456
1403636728563555584
1403636728613555456
1403636728663555584
1403636728713555456
1403636728763555584
1403636728813555456
1403636728863555584
1403636728913555456
1403636728963555584
1403636729013555456
1403636729063555584
1403636729113555456
1403636729163555584
1403636729213555456
1403636729263555584
1403636729313555456
1403636729363555584
1403636729413555456
1403636729463555584
1403636729513555456
1403636729563555584
1403636729613555456
1403636729663555584
1403636729713555456
1403636729763555584
1403636729813555456
1403636729863555584
1403636729913555456
1403636729963555584
1403636730013555456
1403636730063555584
1403636730113555456
1403636730163555584
1403636730213555456
1403636730263555584
1403636730313555456
1403636730363555584
1403636730413555456
1403636730463555584
1403636730513555456
1403636730563555584
1403636730613555456
1403636730663555584
1403636730713555456
1403636730763555584
1403636730813555456
1403636730863555584
1403636730913555456
1403636730963555584
1403636731013555456
1403636731063555584
1403636731113555456
1403636731163555584
1403636731213555456
1403636731263555584
1403636731313555456
1403636731363555584
1403636731413555456
1403636731463555584
1403636731513555456
1403636731563555584
1403636731613555456
1403636731663555584
1403636731713555456
1403636731763555584
1403636731813555456
1403636731863555584
1403636731913555456
1403636731963555584
1403636732013555456
1403636732063555584
1403636732113555456
1403636732163555584
1403636732213555456
1403636732263555584
1403636732313555456
1403636732363555584
1403636732413555456
1403636732463555584
1403636732513555456
1403636732563555584
1403636732613555456
1403636732663555584
1403636732713555456
1403636732763555584
1403636732813555456
1403636732863555584
1403636732913555456
1403636732963555584
1403636733013555456
1403636733063555584
1403636733113555456
1403636733163555584
1403636733213555456
1403636733263555584
1403636733313555456
1403636733363555584
1403636733413555456
1403636733463555584
1403636733513555456
1403636733563555584
1403636733613555456
1403636733663555584
1403636733713555456
1403636733763555584
1403636733813555456
1403636733863555584
1403636733913555456
1403636733963555584
1403636734013555456
1403636734063555584
1403636734113555456
1403636734163555584
1403636734213555456
1403636734263555584
1403636734313555456
1403636734363555584
1403636734413555456
1403636734463555584
1403636734513555456
1403636734563555584
1403636734613555456
1403636734663555584
1403636734713555456
1403636734763555584
1403636734813555456
1403636734863555584
1403636734913555456
1403636734963555584
1403636735013555456
1403636735063555584
1403636735113555456
1403636735163555584
1403636735213555456
1403636735263555584
1403636735313555456
1403636735363555584
1403636735413555456
1403636735463555584
1403636735513555456
1403636735563555584
1403636735613555456
1403636735663555584
1403636735713555456
1403636735763555584
1403636735813555456
1403636735863555584
1403636735913555456
1403636735963555584
1403636736013555456
1403636736063555584
1403636736113555456
1403636736163555584
1403636736213555456
1403636736263555584
1403636736313555456
1403636736363555584
1403636736413555456
1403636736463555584
1403636736513555456
1403636736563555584
1403636736613555456
1403636736663555584
1403636736713555456
1403636736763555584
1403636736813555456
1403636736863555584
1403636736913555456
1403636736963555584
1403636737013555456
1403636737063555584
1403636737113555456
1403636737163555584
1403636737213555456
1403636737263555584
1403636737313555456
1403636737363555584
1403636737413555456
1403636737463555584
1403636737513555456
1403636737563555584
1403636737613555456
1403636737663555584
1403636737713555456
1403636737763555584
1403636737813555456
1403636737863555584
1403636737913555456
1403636737963555584
1403636738013555456
1403636738063555584
1403636738113555456
1403636738163555584
1403636738213555456
1403636738263555584
1403636738313555456
1403636738363555584
1403636738413555456
1403636738463555584
1403636738513555456
1403636738563555584
1403636738613555456
1403636738663555584
1403636738713555456
1403636738763555584
1403636738813555456
1403636738863555584
1403636738913555456
1403636738963555584
1403636739013555456
1403636739063555584
1403636739113555456
1403636739163555584
1403636739213555456
1403636739263555584
1403636739313555456
1403636739363555584
1403636739413555456
1403636739463555584
1403636739513555456
1403636739563555584
1403636739613555456
1403636739663555584
1403636739713555456
1403636739763555584
1403636739813555456
1403636739863555584
1403636739913555456
1403636739963555584
1403636740013555456
1403636740063555584
1403636740113555456
1403636740163555584
1403636740213555456
1403636740263555584
1403636740313555456
1403636740363555584
1403636740413555456
1403636740463555584
1403636740513555456
1403636740563555584
1403636740613555456
1403636740663555584
1403636740713555456
1403636740763555584
1403636740813555456
1403636740863555584
1403636740913555456
1403636740963555584
1403636741013555456
1403636741063555584
1403636741113555456
1403636741163555584
1403636741213555456
1403636741263555584
1403636741313555456
1403636741363555584
1403636741413555456
1403636741463555584
1403636741513555456
1403636741563555584
1403636741613555456
1403636741663555584
1403636741713555456
1403636741763555584
1403636741813555456
1403636741863555584
1403636741913555456
1403636741963555584
1403636742013555456
1403636742063555584
1403636742113555456
1403636742163555584
1403636742213555456
1403636742263555584
1403636742313555456
1403636742363555584
1403636742413555456
1403636742463555584
1403636742513555456
1403636742563555584
1403636742613555456
1403636742663555584
1403636742713555456
1403636742763555584
1403636742813555456
1403636742863555584
1403636742913555456
1403636742963555584
1403636743013555456
1403636743063555584
1403636743113555456
1403636743163555584
1403636743213555456
1403636743263555584
1403636743313555456
1403636743363555584
1403636743413555456
1403636743463555584
1403636743513555456
1403636743563555584
1403636743613555456
1403636743663555584
1403636743713555456
1403636743763555584
1403636743813555456
1403636743863555584
1403636743913555456
1403636743963555584
1403636744013555456
1403636744063555584
1403636744113555456
1403636744163555584
1403636744213555456
1403636744263555584
1403636744313555456
1403636744363555584
1403636744413555456
1403636744463555584
1403636744513555456
1403636744563555584
1403636744613555456
1403636744663555584
1403636744713555456
1403636744763555584
1403636744813555456
1403636744863555584
1403636744913555456
1403636744963555584
1403636745013555456
1403636745063555584
1403636745113555456
1403636745163555584
1403636745213555456
1403636745263555584
1403636745313555456
1403636745363555584
1403636745413555456
1403636745463555584
1403636745513555456
1403636745563555584
1403636745613555456
1403636745663555584
1403636745713555456
1403636745763555584
1403636745813555456
1403636745863555584
1403636745913555456
1403636745963555584
1403636746013555456
1403636746063555584
1403636746113555456
1403636746163555584
1403636746213555456
1403636746263555584
1403636746313555456
1403636746363555584
1403636746413555456
1403636746463555584
1403636746513555456
1403636746563555584
1403636746613555456
1403636746663555584
1403636746713555456
1403636746763555584
1403636746813555456
1403636746863555584
1403636746913555456
1403636746963555584
1403636747013555456
1403636747063555584
1403636747113555456
1403636747163555584
1403636747213555456
1403636747263555584
1403636747313555456
1403636747363555584
1403636747413555456
1403636747463555584
1403636747513555456
1403636747563555584
1403636747613555456
1403636747663555584
1403636747713555456
1403636747763555584
1403636747813555456
1403636747863555584
1403636747913555456
1403636747963555584
1403636748013555456
1403636748063555584
1403636748113555456
1403636748163555584
1403636748213555456
1403636748263555584
1403636748313555456
1403636748363555584
1403636748413555456
1403636748463555584
1403636748513555456
1403636748563555584
1403636748613555456
1403636748663555584
1403636748713555456
1403636748763555584
1403636748813555456
1403636748863555584
1403636748913555456
1403636748963555584
1403636749013555456
1403636749063555584
1403636749113555456
1403636749163555584
1403636749213555456
1403636749263555584
1403636749313555456
1403636749363555584
1403636749413555456
1403636749463555584
1403636749513555456
1403636749563555584
1403636749613555456
1403636749663555584
1403636749713555456
1403636749763555584
1403636749813555456
1403636749863555584
1403636749913555456
1403636749963555584
1403636750013555456
1403636750063555584
1403636750113555456
1403636750163555584
1403636750213555456
1403636750263555584
1403636750313555456
1403636750363555584
1403636750413555456
1403636750463555584
1403636750513555456
1403636750563555584
1403636750613555456
1403636750663555584
1403636750713555456
1403636750763555584
1403636750813555456
1403636750863555584
1403636750913555456
1403636750963555584
1403636751013555456
1403636751063555584
1403636751113555456
1403636751163555584
1403636751213555456
1403636751263555584
1403636751313555456
1403636751363555584
1403636751413555456
1403636751463555584
1403636751513555456
1403636751563555584
1403636751613555456
1403636751663555584
1403636751713555456
1403636751763555584
1403636751813555456
1403636751863555584
1403636751913555456
1403636751963555584
1403636752013555456
1403636752063555584
1403636752113555456
1403636752163555584
1403636752213555456
1403636752263555584
1403636752313555456
1403636752363555584
1403636752413555456
1403636752463555584
1403636752513555456
1403636752563555584
1403636752613555456
1403636752663555584
1403636752713555456
1403636752763555584
1403636752813555456
1403636752863555584
1403636752913555456
1403636752963555584
1403636753013555456
1403636753063555584
1403636753113555456
1403636753163555584
1403636753213555456
1403636753263555584
1403636753313555456
1403636753363555584
1403636753413555456
1403636753463555584
1403636753513555456
1403636753563555584
1403636753613555456
1403636753663555584
1403636753713555456
1403636753763555584
1403636753813555456
1403636753863555584
1403636753913555456
1403636753963555584
1403636754013555456
1403636754063555584
1403636754113555456
1403636754163555584
1403636754213555456
1403636754263555584
1403636754313555456
1403636754363555584
1403636754413555456
1403636754463555584
1403636754513555456
1403636754563555584
1403636754613555456
1403636754663555584
1403636754713555456
1403636754763555584
1403636754813555456
1403636754863555584
1403636754913555456
1403636754963555584
1403636755013555456
1403636755063555584
1403636755113555456
1403636755163555584
1403636755213555456
1403636755263555584
1403636755313555456
1403636755363555584
1403636755413555456
1403636755463555584
1403636755513555456
1403636755563555584
1403636755613555456
1403636755663555584
1403636755713555456
1403636755763555584
1403636755813555456
1403636755863555584
1403636755913555456
1403636755963555584
1403636756013555456
1403636756063555584
1403636756113555456
1403636756163555584
1403636756213555456
1403636756263555584
1403636756313555456
1403636756363555584
1403636756413555456
1403636756463555584
1403636756513555456
1403636756563555584
1403636756613555456
1403636756663555584
1403636756713555456
1403636756763555584
1403636756813555456
1403636756863555584
1403636756913555456
1403636756963555584
1403636757013555456
1403636757063555584
1403636757113555456
1403636757163555584
1403636757213555456
1403636757263555584
1403636757313555456
1403636757363555584
1403636757413555456
1403636757463555584
1403636757513555456
1403636757563555584
1403636757613555456
1403636757663555584
1403636757713555456
1403636757763555584
1403636757813555456
1403636757863555584
1403636757913555456
1403636757963555584
1403636758013555456
1403636758063555584
1403636758113555456
1403636758163555584
1403636758213555456
1403636758263555584
1403636758313555456
1403636758363555584
1403636758413555456
1403636758463555584
1403636758513555456
1403636758563555584
1403636758613555456
1403636758663555584
1403636758713555456
1403636758763555584
1403636758813555456
1403636758863555584
1403636758913555456
1403636758963555584
1403636759013555456
1403636759063555584
1403636759113555456
1403636759163555584
1403636759213555456
1403636759263555584
1403636759313555456
1403636759363555584
1403636759413555456
1403636759463555584
1403636759513555456
1403636759563555584
1403636759613555456
1403636759663555584
1403636759713555456
1403636759763555584
1403636759813555456
1403636759863555584
1403636759913555456
1403636759963555584
1403636760013555456
1403636760063555584
1403636760113555456
1403636760163555584
1403636760213555456
1403636760263555584
1403636760313555456
1403636760363555584
1403636760413555456
1403636760463555584
1403636760513555456
1403636760563555584
1403636760613555456
1403636760663555584
1403636760713555456
1403636760763555584
1403636760813555456
1403636760863555584
1403636760913555456
1403636760963555584
1403636761013555456
1403636761063555584
1403636761113555456
1403636761163555584
1403636761213555456
1403636761263555584
1403636761313555456
1403636761363555584
1403636761413555456
1403636761463555584
1403636761513555456
1403636761563555584
1403636761613555456
1403636761663555584
1403636761713555456
1403636761763555584
1403636761813555456
1403636761863555584
1403636761913555456
1403636761963555584
1403636762013555456
1403636762063555584
1403636762113555456
1403636762163555584
1403636762213555456
1403636762263555584
1403636762313555456
1403636762363555584
1403636762413555456
1403636762463555584
1403636762513555456
1403636762563555584
1403636762613555456
1403636762663555584
1403636762713555456
1403636762763555584
1403636762813555456
1403636762863555584
1403636762913555456
1403636762963555584
1403636763013555456
1403636763063555584
1403636763113555456
1403636763163555584
1403636763213555456
1403636763263555584
1403636763313555456
1403636763363555584
1403636763413555456
1403636763463555584
1403636763513555456
1403636763563555584
1403636763613555456
1403636763663555584
1403636763713555456
1403636763763555584
1403636763813555456
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/MH02.txt
================================================
1403636858651666432
1403636858701666560
1403636858751666432
1403636858801666560
1403636858851666432
1403636858901666560
1403636858951666432
1403636859001666560
1403636859051666432
1403636859101666560
1403636859151666432
1403636859201666560
1403636859251666432
1403636859301666560
1403636859351666432
1403636859401666560
1403636859451666432
1403636859501666560
1403636859551666432
1403636859601666560
1403636859651666432
1403636859701666560
1403636859751666432
1403636859801666560
1403636859851666432
1403636859901666560
1403636859951666432
1403636860001666560
1403636860051666432
1403636860101666560
1403636860151666432
1403636860201666560
1403636860251666432
1403636860301666560
1403636860351666432
1403636860401666560
1403636860451666432
1403636860501666560
1403636860551666432
1403636860601666560
1403636860651666432
1403636860701666560
1403636860751666432
1403636860801666560
1403636860851666432
1403636860901666560
1403636860951666432
1403636861001666560
1403636861051666432
1403636861101666560
1403636861151666432
1403636861201666560
1403636861251666432
1403636861301666560
1403636861351666432
1403636861401666560
1403636861451666432
1403636861501666560
1403636861551666432
1403636861601666560
1403636861651666432
1403636861701666560
1403636861751666432
1403636861801666560
1403636861851666432
1403636861901666560
1403636861951666432
1403636862001666560
1403636862051666432
1403636862101666560
1403636862151666432
1403636862201666560
1403636862251666432
1403636862301666560
1403636862351666432
1403636862401666560
1403636862451666432
1403636862501666560
1403636862551666432
1403636862601666560
1403636862651666432
1403636862701666560
1403636862751666432
1403636862801666560
1403636862851666432
1403636862901666560
1403636862951666432
1403636863001666560
1403636863051666432
1403636863101666560
1403636863151666432
1403636863201666560
1403636863251666432
1403636863301666560
1403636863351666432
1403636863401666560
1403636863451666432
1403636863501666560
1403636863551666432
1403636863601666560
1403636863651666432
1403636863701666560
1403636863751666432
1403636863801666560
1403636863851666432
1403636863901666560
1403636863951666432
1403636864001666560
1403636864051666432
1403636864101666560
1403636864151666432
1403636864201666560
1403636864251666432
1403636864301666560
1403636864351666432
1403636864401666560
1403636864451666432
1403636864501666560
1403636864551666432
1403636864601666560
1403636864651666432
1403636864701666560
1403636864751666432
1403636864801666560
1403636864851666432
1403636864901666560
1403636864951666432
1403636865001666560
1403636865051666432
1403636865101666560
1403636865151666432
1403636865201666560
1403636865251666432
1403636865301666560
1403636865351666432
1403636865401666560
1403636865451666432
1403636865501666560
1403636865551666432
1403636865601666560
1403636865651666432
1403636865701666560
1403636865751666432
1403636865801666560
1403636865851666432
1403636865901666560
1403636865951666432
1403636866001666560
1403636866051666432
1403636866101666560
1403636866151666432
1403636866201666560
1403636866251666432
1403636866301666560
1403636866351666432
1403636866401666560
1403636866451666432
1403636866501666560
1403636866551666432
1403636866601666560
1403636866651666432
1403636866701666560
1403636866751666432
1403636866801666560
1403636866851666432
1403636866901666560
1403636866951666432
1403636867001666560
1403636867051666432
1403636867101666560
1403636867151666432
1403636867201666560
1403636867251666432
1403636867301666560
1403636867351666432
1403636867401666560
1403636867451666432
1403636867501666560
1403636867551666432
1403636867601666560
1403636867651666432
1403636867701666560
1403636867751666432
1403636867801666560
1403636867851666432
1403636867901666560
1403636867951666432
1403636868001666560
1403636868051666432
1403636868101666560
1403636868151666432
1403636868201666560
1403636868251666432
1403636868301666560
1403636868351666432
1403636868401666560
1403636868451666432
1403636868501666560
1403636868551666432
1403636868601666560
1403636868651666432
1403636868701666560
1403636868751666432
1403636868801666560
1403636868851666432
1403636868901666560
1403636868951666432
1403636869001666560
1403636869051666432
1403636869101666560
1403636869151666432
1403636869201666560
1403636869251666432
1403636869301666560
1403636869351666432
1403636869401666560
1403636869451666432
1403636869501666560
1403636869551666432
1403636869601666560
1403636869651666432
1403636869701666560
1403636869751666432
1403636869801666560
1403636869851666432
1403636869901666560
1403636869951666432
1403636870001666560
1403636870051666432
1403636870101666560
1403636870151666432
1403636870201666560
1403636870251666432
1403636870301666560
1403636870351666432
1403636870401666560
1403636870451666432
1403636870501666560
1403636870551666432
1403636870601666560
1403636870651666432
1403636870701666560
1403636870751666432
1403636870801666560
1403636870851666432
1403636870901666560
1403636870951666432
1403636871001666560
1403636871051666432
1403636871101666560
1403636871151666432
1403636871201666560
1403636871251666432
1403636871301666560
1403636871351666432
1403636871401666560
1403636871451666432
1403636871501666560
1403636871551666432
1403636871601666560
1403636871651666432
1403636871701666560
1403636871751666432
1403636871801666560
1403636871851666432
1403636871901666560
1403636871951666432
1403636872001666560
1403636872051666432
1403636872101666560
1403636872151666432
1403636872201666560
1403636872251666432
1403636872301666560
1403636872351666432
1403636872401666560
1403636872451666432
1403636872501666560
1403636872551666432
1403636872601666560
1403636872651666432
1403636872701666560
1403636872751666432
1403636872801666560
1403636872851666432
1403636872901666560
1403636872951666432
1403636873001666560
1403636873051666432
1403636873101666560
1403636873151666432
1403636873201666560
1403636873251666432
1403636873301666560
1403636873351666432
1403636873401666560
1403636873451666432
1403636873501666560
1403636873551666432
1403636873601666560
1403636873651666432
1403636873701666560
1403636873751666432
1403636873801666560
1403636873851666432
1403636873901666560
1403636873951666432
1403636874001666560
1403636874051666432
1403636874101666560
1403636874151666432
1403636874201666560
1403636874251666432
1403636874301666560
1403636874351666432
1403636874401666560
1403636874451666432
1403636874501666560
1403636874551666432
1403636874601666560
1403636874651666432
1403636874701666560
1403636874751666432
1403636874801666560
1403636874851666432
1403636874901666560
1403636874951666432
1403636875001666560
1403636875051666432
1403636875101666560
1403636875151666432
1403636875201666560
1403636875251666432
1403636875301666560
1403636875351666432
1403636875401666560
1403636875451666432
1403636875501666560
1403636875551666432
1403636875601666560
1403636875651666432
1403636875701666560
1403636875751666432
1403636875801666560
1403636875851666432
1403636875901666560
1403636875951666432
1403636876001666560
1403636876051666432
1403636876101666560
1403636876151666432
1403636876201666560
1403636876251666432
1403636876301666560
1403636876351666432
1403636876401666560
1403636876451666432
1403636876501666560
1403636876551666432
1403636876601666560
1403636876651666432
1403636876701666560
1403636876751666432
1403636876801666560
1403636876851666432
1403636876901666560
1403636876951666432
1403636877001666560
1403636877051666432
1403636877101666560
1403636877151666432
1403636877201666560
1403636877251666432
1403636877301666560
1403636877351666432
1403636877401666560
1403636877451666432
1403636877501666560
1403636877551666432
1403636877601666560
1403636877651666432
1403636877701666560
1403636877751666432
1403636877801666560
1403636877851666432
1403636877901666560
1403636877951666432
1403636878001666560
1403636878051666432
1403636878101666560
1403636878151666432
1403636878201666560
1403636878251666432
1403636878301666560
1403636878351666432
1403636878401666560
1403636878451666432
1403636878501666560
1403636878551666432
1403636878601666560
1403636878651666432
1403636878701666560
1403636878751666432
1403636878801666560
1403636878851666432
1403636878901666560
1403636878951666432
1403636879001666560
1403636879051666432
1403636879101666560
1403636879151666432
1403636879201666560
1403636879251666432
1403636879301666560
1403636879351666432
1403636879401666560
1403636879451666432
1403636879501666560
1403636879551666432
1403636879601666560
1403636879651666432
1403636879701666560
1403636879751666432
1403636879801666560
1403636879851666432
1403636879901666560
1403636879951666432
1403636880001666560
1403636880051666432
1403636880101666560
1403636880151666432
1403636880201666560
1403636880251666432
1403636880301666560
1403636880351666432
1403636880401666560
1403636880451666432
1403636880501666560
1403636880551666432
1403636880601666560
1403636880651666432
1403636880701666560
1403636880751666432
1403636880801666560
1403636880851666432
1403636880901666560
1403636880951666432
1403636881001666560
1403636881051666432
1403636881101666560
1403636881151666432
1403636881201666560
1403636881251666432
1403636881301666560
1403636881351666432
1403636881401666560
1403636881451666432
1403636881501666560
1403636881551666432
1403636881601666560
1403636881651666432
1403636881701666560
1403636881751666432
1403636881801666560
1403636881851666432
1403636881901666560
1403636881951666432
1403636882001666560
1403636882051666432
1403636882101666560
1403636882151666432
1403636882201666560
1403636882251666432
1403636882301666560
1403636882351666432
1403636882401666560
1403636882451666432
1403636882501666560
1403636882551666432
1403636882601666560
1403636882651666432
1403636882701666560
1403636882751666432
1403636882801666560
1403636882851666432
1403636882901666560
1403636882951666432
1403636883001666560
1403636883051666432
1403636883101666560
1403636883151666432
1403636883201666560
1403636883251666432
1403636883301666560
1403636883351666432
1403636883401666560
1403636883451666432
1403636883501666560
1403636883551666432
1403636883601666560
1403636883651666432
1403636883701666560
1403636883751666432
1403636883801666560
1403636883851666432
1403636883901666560
1403636883951666432
1403636884001666560
1403636884051666432
1403636884101666560
1403636884151666432
1403636884201666560
1403636884251666432
1403636884301666560
1403636884351666432
1403636884401666560
1403636884451666432
1403636884501666560
1403636884551666432
1403636884601666560
1403636884651666432
1403636884701666560
1403636884751666432
1403636884801666560
1403636884851666432
1403636884901666560
1403636884951666432
1403636885001666560
1403636885051666432
1403636885101666560
1403636885151666432
1403636885201666560
1403636885251666432
1403636885301666560
1403636885351666432
1403636885401666560
1403636885451666432
1403636885501666560
1403636885551666432
1403636885601666560
1403636885651666432
1403636885701666560
1403636885751666432
1403636885801666560
1403636885851666432
1403636885901666560
1403636885951666432
1403636886001666560
1403636886051666432
1403636886101666560
1403636886151666432
1403636886201666560
1403636886251666432
1403636886301666560
1403636886351666432
1403636886401666560
1403636886451666432
1403636886501666560
1403636886551666432
1403636886601666560
1403636886651666432
1403636886701666560
1403636886751666432
1403636886801666560
1403636886851666432
1403636886901666560
1403636886951666432
1403636887001666560
1403636887051666432
1403636887101666560
1403636887151666432
1403636887201666560
1403636887251666432
1403636887301666560
1403636887351666432
1403636887401666560
1403636887451666432
1403636887501666560
1403636887551666432
1403636887601666560
1403636887651666432
1403636887701666560
1403636887751666432
1403636887801666560
1403636887851666432
1403636887901666560
1403636887951666432
1403636888001666560
1403636888051666432
1403636888101666560
1403636888151666432
1403636888201666560
1403636888251666432
1403636888301666560
1403636888351666432
1403636888401666560
1403636888451666432
1403636888501666560
1403636888551666432
1403636888601666560
1403636888651666432
1403636888701666560
1403636888751666432
1403636888801666560
1403636888851666432
1403636888901666560
1403636888951666432
1403636889001666560
1403636889051666432
1403636889101666560
1403636889151666432
1403636889201666560
1403636889251666432
1403636889301666560
1403636889351666432
1403636889401666560
1403636889451666432
1403636889501666560
1403636889551666432
1403636889601666560
1403636889651666432
1403636889701666560
1403636889751666432
1403636889801666560
1403636889851666432
1403636889901666560
1403636889951666432
1403636890001666560
1403636890051666432
1403636890101666560
1403636890151666432
1403636890201666560
1403636890251666432
1403636890301666560
1403636890351666432
1403636890401666560
1403636890451666432
1403636890501666560
1403636890551666432
1403636890601666560
1403636890651666432
1403636890701666560
1403636890751666432
1403636890801666560
1403636890851666432
1403636890901666560
1403636890951666432
1403636891001666560
1403636891051666432
1403636891101666560
1403636891151666432
1403636891201666560
1403636891251666432
1403636891301666560
1403636891351666432
1403636891401666560
1403636891451666432
1403636891501666560
1403636891551666432
1403636891601666560
1403636891651666432
1403636891701666560
1403636891751666432
1403636891801666560
1403636891851666432
1403636891901666560
1403636891951666432
1403636892001666560
1403636892051666432
1403636892101666560
1403636892151666432
1403636892201666560
1403636892251666432
1403636892301666560
1403636892351666432
1403636892401666560
1403636892451666432
1403636892501666560
1403636892551666432
1403636892601666560
1403636892651666432
1403636892701666560
1403636892751666432
1403636892801666560
1403636892851666432
1403636892901666560
1403636892951666432
1403636893001666560
1403636893051666432
1403636893101666560
1403636893151666432
1403636893201666560
1403636893251666432
1403636893301666560
1403636893351666432
1403636893401666560
1403636893451666432
1403636893501666560
1403636893551666432
1403636893601666560
1403636893651666432
1403636893701666560
1403636893751666432
1403636893801666560
1403636893851666432
1403636893901666560
1403636893951666432
1403636894001666560
1403636894051666432
1403636894101666560
1403636894151666432
1403636894201666560
1403636894251666432
1403636894301666560
1403636894351666432
1403636894401666560
1403636894451666432
1403636894501666560
1403636894551666432
1403636894601666560
1403636894651666432
1403636894701666560
1403636894751666432
1403636894801666560
1403636894851666432
1403636894901666560
1403636894951666432
1403636895001666560
1403636895051666432
1403636895101666560
1403636895151666432
1403636895201666560
1403636895251666432
1403636895301666560
1403636895351666432
1403636895401666560
1403636895451666432
1403636895501666560
1403636895551666432
1403636895601666560
1403636895651666432
1403636895701666560
1403636895751666432
1403636895801666560
1403636895851666432
1403636895901666560
1403636895951666432
1403636896001666560
1403636896051666432
1403636896101666560
1403636896151666432
1403636896201666560
1403636896251666432
1403636896301666560
1403636896351666432
1403636896401666560
1403636896451666432
1403636896501666560
1403636896551666432
1403636896601666560
1403636896651666432
1403636896701666560
1403636896751666432
1403636896801666560
1403636896851666432
1403636896901666560
1403636896951666432
1403636897001666560
1403636897051666432
1403636897101666560
1403636897151666432
1403636897201666560
1403636897251666432
1403636897301666560
1403636897351666432
1403636897401666560
1403636897451666432
1403636897501666560
1403636897551666432
1403636897601666560
1403636897651666432
1403636897701666560
1403636897751666432
1403636897801666560
1403636897851666432
1403636897901666560
1403636897951666432
1403636898001666560
1403636898051666432
1403636898101666560
1403636898151666432
1403636898201666560
1403636898251666432
1403636898301666560
1403636898351666432
1403636898401666560
1403636898451666432
1403636898501666560
1403636898551666432
1403636898601666560
1403636898651666432
1403636898701666560
1403636898751666432
1403636898801666560
1403636898851666432
1403636898901666560
1403636898951666432
1403636899001666560
1403636899051666432
1403636899101666560
1403636899151666432
1403636899201666560
1403636899251666432
1403636899301666560
1403636899351666432
1403636899401666560
1403636899451666432
1403636899501666560
1403636899551666432
1403636899601666560
1403636899651666432
1403636899701666560
1403636899751666432
1403636899801666560
1403636899851666432
1403636899901666560
1403636899951666432
1403636900001666560
1403636900051666432
1403636900101666560
1403636900151666432
1403636900201666560
1403636900251666432
1403636900301666560
1403636900351666432
1403636900401666560
1403636900451666432
1403636900501666560
1403636900551666432
1403636900601666560
1403636900651666432
1403636900701666560
1403636900751666432
1403636900801666560
1403636900851666432
1403636900901666560
1403636900951666432
1403636901001666560
1403636901051666432
1403636901101666560
1403636901151666432
1403636901201666560
1403636901251666432
1403636901301666560
1403636901351666432
1403636901401666560
1403636901451666432
1403636901501666560
1403636901551666432
1403636901601666560
1403636901651666432
1403636901701666560
1403636901751666432
1403636901801666560
1403636901851666432
1403636901901666560
1403636901951666432
1403636902001666560
1403636902051666432
1403636902101666560
1403636902151666432
1403636902201666560
1403636902251666432
1403636902301666560
1403636902351666432
1403636902401666560
1403636902451666432
1403636902501666560
1403636902551666432
1403636902601666560
1403636902651666432
1403636902701666560
1403636902751666432
1403636902801666560
1403636902851666432
1403636902901666560
1403636902951666432
1403636903001666560
1403636903051666432
1403636903101666560
1403636903151666432
1403636903201666560
1403636903251666432
1403636903301666560
1403636903351666432
1403636903401666560
1403636903451666432
1403636903501666560
1403636903551666432
1403636903601666560
1403636903651666432
1403636903701666560
1403636903751666432
1403636903801666560
1403636903851666432
1403636903901666560
1403636903951666432
1403636904001666560
1403636904051666432
1403636904101666560
1403636904151666432
1403636904201666560
1403636904251666432
1403636904301666560
1403636904351666432
1403636904401666560
1403636904451666432
1403636904501666560
1403636904551666432
1403636904601666560
1403636904651666432
1403636904701666560
1403636904751666432
1403636904801666560
1403636904851666432
1403636904901666560
1403636904951666432
1403636905001666560
1403636905051666432
1403636905101666560
1403636905151666432
1403636905201666560
1403636905251666432
1403636905301666560
1403636905351666432
1403636905401666560
1403636905451666432
1403636905501666560
1403636905551666432
1403636905601666560
1403636905651666432
1403636905701666560
1403636905751666432
1403636905801666560
1403636905851666432
1403636905901666560
1403636905951666432
1403636906001666560
1403636906051666432
1403636906101666560
1403636906151666432
1403636906201666560
1403636906251666432
1403636906301666560
1403636906351666432
1403636906401666560
1403636906451666432
1403636906501666560
1403636906551666432
1403636906601666560
1403636906651666432
1403636906701666560
1403636906751666432
1403636906801666560
1403636906851666432
1403636906901666560
1403636906951666432
1403636907001666560
1403636907051666432
1403636907101666560
1403636907151666432
1403636907201666560
1403636907251666432
1403636907301666560
1403636907351666432
1403636907401666560
1403636907451666432
1403636907501666560
1403636907551666432
1403636907601666560
1403636907651666432
1403636907701666560
1403636907751666432
1403636907801666560
1403636907851666432
1403636907901666560
1403636907951666432
1403636908001666560
1403636908051666432
1403636908101666560
1403636908151666432
1403636908201666560
1403636908251666432
1403636908301666560
1403636908351666432
1403636908401666560
1403636908451666432
1403636908501666560
1403636908551666432
1403636908601666560
1403636908651666432
1403636908701666560
1403636908751666432
1403636908801666560
1403636908851666432
1403636908901666560
1403636908951666432
1403636909001666560
1403636909051666432
1403636909101666560
1403636909151666432
1403636909201666560
1403636909251666432
1403636909301666560
1403636909351666432
1403636909401666560
1403636909451666432
1403636909501666560
1403636909551666432
1403636909601666560
1403636909651666432
1403636909701666560
1403636909751666432
1403636909801666560
1403636909851666432
1403636909901666560
1403636909951666432
1403636910001666560
1403636910051666432
1403636910101666560
1403636910151666432
1403636910201666560
1403636910251666432
1403636910301666560
1403636910351666432
1403636910401666560
1403636910451666432
1403636910501666560
1403636910551666432
1403636910601666560
1403636910651666432
1403636910701666560
1403636910751666432
1403636910801666560
1403636910851666432
1403636910901666560
1403636910951666432
1403636911001666560
1403636911051666432
1403636911101666560
1403636911151666432
1403636911201666560
1403636911251666432
1403636911301666560
1403636911351666432
1403636911401666560
1403636911451666432
1403636911501666560
1403636911551666432
1403636911601666560
1403636911651666432
1403636911701666560
1403636911751666432
1403636911801666560
1403636911851666432
1403636911901666560
1403636911951666432
1403636912001666560
1403636912051666432
1403636912101666560
1403636912151666432
1403636912201666560
1403636912251666432
1403636912301666560
1403636912351666432
1403636912401666560
1403636912451666432
1403636912501666560
1403636912551666432
1403636912601666560
1403636912651666432
1403636912701666560
1403636912751666432
1403636912801666560
1403636912851666432
1403636912901666560
1403636912951666432
1403636913001666560
1403636913051666432
1403636913101666560
1403636913151666432
1403636913201666560
1403636913251666432
1403636913301666560
1403636913351666432
1403636913401666560
1403636913451666432
1403636913501666560
1403636913551666432
1403636913601666560
1403636913651666432
1403636913701666560
1403636913751666432
1403636913801666560
1403636913851666432
1403636913901666560
1403636913951666432
1403636914001666560
1403636914051666432
1403636914101666560
1403636914151666432
1403636914201666560
1403636914251666432
1403636914301666560
1403636914351666432
1403636914401666560
1403636914451666432
1403636914501666560
1403636914551666432
1403636914601666560
1403636914651666432
1403636914701666560
1403636914751666432
1403636914801666560
1403636914851666432
1403636914901666560
1403636914951666432
1403636915001666560
1403636915051666432
1403636915101666560
1403636915151666432
1403636915201666560
1403636915251666432
1403636915301666560
1403636915351666432
1403636915401666560
1403636915451666432
1403636915501666560
1403636915551666432
1403636915601666560
1403636915651666432
1403636915701666560
1403636915751666432
1403636915801666560
1403636915851666432
1403636915901666560
1403636915951666432
1403636916001666560
1403636916051666432
1403636916101666560
1403636916151666432
1403636916201666560
1403636916251666432
1403636916301666560
1403636916351666432
1403636916401666560
1403636916451666432
1403636916501666560
1403636916551666432
1403636916601666560
1403636916651666432
1403636916701666560
1403636916751666432
1403636916801666560
1403636916851666432
1403636916901666560
1403636916951666432
1403636917001666560
1403636917051666432
1403636917101666560
1403636917151666432
1403636917201666560
1403636917251666432
1403636917301666560
1403636917351666432
1403636917401666560
1403636917451666432
1403636917501666560
1403636917551666432
1403636917601666560
1403636917651666432
1403636917701666560
1403636917751666432
1403636917801666560
1403636917851666432
1403636917901666560
1403636917951666432
1403636918001666560
1403636918051666432
1403636918101666560
1403636918151666432
1403636918201666560
1403636918251666432
1403636918301666560
1403636918351666432
1403636918401666560
1403636918451666432
1403636918501666560
1403636918551666432
1403636918601666560
1403636918651666432
1403636918701666560
1403636918751666432
1403636918801666560
1403636918851666432
1403636918901666560
1403636918951666432
1403636919001666560
1403636919051666432
1403636919101666560
1403636919151666432
1403636919201666560
1403636919251666432
1403636919301666560
1403636919351666432
1403636919401666560
1403636919451666432
1403636919501666560
1403636919551666432
1403636919601666560
1403636919651666432
1403636919701666560
1403636919751666432
1403636919801666560
1403636919851666432
1403636919901666560
1403636919951666432
1403636920001666560
1403636920051666432
1403636920101666560
1403636920151666432
1403636920201666560
1403636920251666432
1403636920301666560
1403636920351666432
1403636920401666560
1403636920451666432
1403636920501666560
1403636920551666432
1403636920601666560
1403636920651666432
1403636920701666560
1403636920751666432
1403636920801666560
1403636920851666432
1403636920901666560
1403636920951666432
1403636921001666560
1403636921051666432
1403636921101666560
1403636921151666432
1403636921201666560
1403636921251666432
1403636921301666560
1403636921351666432
1403636921401666560
1403636921451666432
1403636921501666560
1403636921551666432
1403636921601666560
1403636921651666432
1403636921701666560
1403636921751666432
1403636921801666560
1403636921851666432
1403636921901666560
1403636921951666432
1403636922001666560
1403636922051666432
1403636922101666560
1403636922151666432
1403636922201666560
1403636922251666432
1403636922301666560
1403636922351666432
1403636922401666560
1403636922451666432
1403636922501666560
1403636922551666432
1403636922601666560
1403636922651666432
1403636922701666560
1403636922751666432
1403636922801666560
1403636922851666432
1403636922901666560
1403636922951666432
1403636923001666560
1403636923051666432
1403636923101666560
1403636923151666432
1403636923201666560
1403636923251666432
1403636923301666560
1403636923351666432
1403636923401666560
1403636923451666432
1403636923501666560
1403636923551666432
1403636923601666560
1403636923651666432
1403636923701666560
1403636923751666432
1403636923801666560
1403636923851666432
1403636923901666560
1403636923951666432
1403636924001666560
1403636924051666432
1403636924101666560
1403636924151666432
1403636924201666560
1403636924251666432
1403636924301666560
1403636924351666432
1403636924401666560
1403636924451666432
1403636924501666560
1403636924551666432
1403636924601666560
1403636924651666432
1403636924701666560
1403636924751666432
1403636924801666560
1403636924851666432
1403636924901666560
1403636924951666432
1403636925001666560
1403636925051666432
1403636925101666560
1403636925151666432
1403636925201666560
1403636925251666432
1403636925301666560
1403636925351666432
1403636925401666560
1403636925451666432
1403636925501666560
1403636925551666432
1403636925601666560
1403636925651666432
1403636925701666560
1403636925751666432
1403636925801666560
1403636925851666432
1403636925901666560
1403636925951666432
1403636926001666560
1403636926051666432
1403636926101666560
1403636926151666432
1403636926201666560
1403636926251666432
1403636926301666560
1403636926351666432
1403636926401666560
1403636926451666432
1403636926501666560
1403636926551666432
1403636926601666560
1403636926651666432
1403636926701666560
1403636926751666432
1403636926801666560
1403636926851666432
1403636926901666560
1403636926951666432
1403636927001666560
1403636927051666432
1403636927101666560
1403636927151666432
1403636927201666560
1403636927251666432
1403636927301666560
1403636927351666432
1403636927401666560
1403636927451666432
1403636927501666560
1403636927551666432
1403636927601666560
1403636927651666432
1403636927701666560
1403636927751666432
1403636927801666560
1403636927851666432
1403636927901666560
1403636927951666432
1403636928001666560
1403636928051666432
1403636928101666560
1403636928151666432
1403636928201666560
1403636928251666432
1403636928301666560
1403636928351666432
1403636928401666560
1403636928451666432
1403636928501666560
1403636928551666432
1403636928601666560
1403636928651666432
1403636928701666560
1403636928751666432
1403636928801666560
1403636928851666432
1403636928901666560
1403636928951666432
1403636929001666560
1403636929051666432
1403636929101666560
1403636929151666432
1403636929201666560
1403636929251666432
1403636929301666560
1403636929351666432
1403636929401666560
1403636929451666432
1403636929501666560
1403636929551666432
1403636929601666560
1403636929651666432
1403636929701666560
1403636929751666432
1403636929801666560
1403636929851666432
1403636929901666560
1403636929951666432
1403636930001666560
1403636930051666432
1403636930101666560
1403636930151666432
1403636930201666560
1403636930251666432
1403636930301666560
1403636930351666432
1403636930401666560
1403636930451666432
1403636930501666560
1403636930551666432
1403636930601666560
1403636930651666432
1403636930701666560
1403636930751666432
1403636930801666560
1403636930851666432
1403636930901666560
1403636930951666432
1403636931001666560
1403636931051666432
1403636931101666560
1403636931151666432
1403636931201666560
1403636931251666432
1403636931301666560
1403636931351666432
1403636931401666560
1403636931451666432
1403636931501666560
1403636931551666432
1403636931601666560
1403636931651666432
1403636931701666560
1403636931751666432
1403636931801666560
1403636931851666432
1403636931901666560
1403636931951666432
1403636932001666560
1403636932051666432
1403636932101666560
1403636932151666432
1403636932201666560
1403636932251666432
1403636932301666560
1403636932351666432
1403636932401666560
1403636932451666432
1403636932501666560
1403636932551666432
1403636932601666560
1403636932651666432
1403636932701666560
1403636932751666432
1403636932801666560
1403636932851666432
1403636932901666560
1403636932951666432
1403636933001666560
1403636933051666432
1403636933101666560
1403636933151666432
1403636933201666560
1403636933251666432
1403636933301666560
1403636933351666432
1403636933401666560
1403636933451666432
1403636933501666560
1403636933551666432
1403636933601666560
1403636933651666432
1403636933701666560
1403636933751666432
1403636933801666560
1403636933851666432
1403636933901666560
1403636933951666432
1403636934001666560
1403636934051666432
1403636934101666560
1403636934151666432
1403636934201666560
1403636934251666432
1403636934301666560
1403636934351666432
1403636934401666560
1403636934451666432
1403636934501666560
1403636934551666432
1403636934601666560
1403636934651666432
1403636934701666560
1403636934751666432
1403636934801666560
1403636934851666432
1403636934901666560
1403636934951666432
1403636935001666560
1403636935051666432
1403636935101666560
1403636935151666432
1403636935201666560
1403636935251666432
1403636935301666560
1403636935351666432
1403636935401666560
1403636935451666432
1403636935501666560
1403636935551666432
1403636935601666560
1403636935651666432
1403636935701666560
1403636935751666432
1403636935801666560
1403636935851666432
1403636935901666560
1403636935951666432
1403636936001666560
1403636936051666432
1403636936101666560
1403636936151666432
1403636936201666560
1403636936251666432
1403636936301666560
1403636936351666432
1403636936401666560
1403636936451666432
1403636936501666560
1403636936551666432
1403636936601666560
1403636936651666432
1403636936701666560
1403636936751666432
1403636936801666560
1403636936851666432
1403636936901666560
1403636936951666432
1403636937001666560
1403636937051666432
1403636937101666560
1403636937151666432
1403636937201666560
1403636937251666432
1403636937301666560
1403636937351666432
1403636937401666560
1403636937451666432
1403636937501666560
1403636937551666432
1403636937601666560
1403636937651666432
1403636937701666560
1403636937751666432
1403636937801666560
1403636937851666432
1403636937901666560
1403636937951666432
1403636938001666560
1403636938051666432
1403636938101666560
1403636938151666432
1403636938201666560
1403636938251666432
1403636938301666560
1403636938351666432
1403636938401666560
1403636938451666432
1403636938501666560
1403636938551666432
1403636938601666560
1403636938651666432
1403636938701666560
1403636938751666432
1403636938801666560
1403636938851666432
1403636938901666560
1403636938951666432
1403636939001666560
1403636939051666432
1403636939101666560
1403636939151666432
1403636939201666560
1403636939251666432
1403636939301666560
1403636939351666432
1403636939401666560
1403636939451666432
1403636939501666560
1403636939551666432
1403636939601666560
1403636939651666432
1403636939701666560
1403636939751666432
1403636939801666560
1403636939851666432
1403636939901666560
1403636939951666432
1403636940001666560
1403636940051666432
1403636940101666560
1403636940151666432
1403636940201666560
1403636940251666432
1403636940301666560
1403636940351666432
1403636940401666560
1403636940451666432
1403636940501666560
1403636940551666432
1403636940601666560
1403636940651666432
1403636940701666560
1403636940751666432
1403636940801666560
1403636940851666432
1403636940901666560
1403636940951666432
1403636941001666560
1403636941051666432
1403636941101666560
1403636941151666432
1403636941201666560
1403636941251666432
1403636941301666560
1403636941351666432
1403636941401666560
1403636941451666432
1403636941501666560
1403636941551666432
1403636941601666560
1403636941651666432
1403636941701666560
1403636941751666432
1403636941801666560
1403636941851666432
1403636941901666560
1403636941951666432
1403636942001666560
1403636942051666432
1403636942101666560
1403636942151666432
1403636942201666560
1403636942251666432
1403636942301666560
1403636942351666432
1403636942401666560
1403636942451666432
1403636942501666560
1403636942551666432
1403636942601666560
1403636942651666432
1403636942701666560
1403636942751666432
1403636942801666560
1403636942851666432
1403636942901666560
1403636942951666432
1403636943001666560
1403636943051666432
1403636943101666560
1403636943151666432
1403636943201666560
1403636943251666432
1403636943301666560
1403636943351666432
1403636943401666560
1403636943451666432
1403636943501666560
1403636943551666432
1403636943601666560
1403636943651666432
1403636943701666560
1403636943751666432
1403636943801666560
1403636943851666432
1403636943901666560
1403636943951666432
1403636944001666560
1403636944051666432
1403636944101666560
1403636944151666432
1403636944201666560
1403636944251666432
1403636944301666560
1403636944351666432
1403636944401666560
1403636944451666432
1403636944501666560
1403636944551666432
1403636944601666560
1403636944651666432
1403636944701666560
1403636944751666432
1403636944801666560
1403636944851666432
1403636944901666560
1403636944951666432
1403636945001666560
1403636945051666432
1403636945101666560
1403636945151666432
1403636945201666560
1403636945251666432
1403636945301666560
1403636945351666432
1403636945401666560
1403636945451666432
1403636945501666560
1403636945551666432
1403636945601666560
1403636945651666432
1403636945701666560
1403636945751666432
1403636945801666560
1403636945851666432
1403636945901666560
1403636945951666432
1403636946001666560
1403636946051666432
1403636946101666560
1403636946151666432
1403636946201666560
1403636946251666432
1403636946301666560
1403636946351666432
1403636946401666560
1403636946451666432
1403636946501666560
1403636946551666432
1403636946601666560
1403636946651666432
1403636946701666560
1403636946751666432
1403636946801666560
1403636946851666432
1403636946901666560
1403636946951666432
1403636947001666560
1403636947051666432
1403636947101666560
1403636947151666432
1403636947201666560
1403636947251666432
1403636947301666560
1403636947351666432
1403636947401666560
1403636947451666432
1403636947501666560
1403636947551666432
1403636947601666560
1403636947651666432
1403636947701666560
1403636947751666432
1403636947801666560
1403636947851666432
1403636947901666560
1403636947951666432
1403636948001666560
1403636948051666432
1403636948101666560
1403636948151666432
1403636948201666560
1403636948251666432
1403636948301666560
1403636948351666432
1403636948401666560
1403636948451666432
1403636948501666560
1403636948551666432
1403636948601666560
1403636948651666432
1403636948701666560
1403636948751666432
1403636948801666560
1403636948851666432
1403636948901666560
1403636948951666432
1403636949001666560
1403636949051666432
1403636949101666560
1403636949151666432
1403636949201666560
1403636949251666432
1403636949301666560
1403636949351666432
1403636949401666560
1403636949451666432
1403636949501666560
1403636949551666432
1403636949601666560
1403636949651666432
1403636949701666560
1403636949751666432
1403636949801666560
1403636949851666432
1403636949901666560
1403636949951666432
1403636950001666560
1403636950051666432
1403636950101666560
1403636950151666432
1403636950201666560
1403636950251666432
1403636950301666560
1403636950351666432
1403636950401666560
1403636950451666432
1403636950501666560
1403636950551666432
1403636950601666560
1403636950651666432
1403636950701666560
1403636950751666432
1403636950801666560
1403636950851666432
1403636950901666560
1403636950951666432
1403636951001666560
1403636951051666432
1403636951101666560
1403636951151666432
1403636951201666560
1403636951251666432
1403636951301666560
1403636951351666432
1403636951401666560
1403636951451666432
1403636951501666560
1403636951551666432
1403636951601666560
1403636951651666432
1403636951701666560
1403636951751666432
1403636951801666560
1403636951851666432
1403636951901666560
1403636951951666432
1403636952001666560
1403636952051666432
1403636952101666560
1403636952151666432
1403636952201666560
1403636952251666432
1403636952301666560
1403636952351666432
1403636952401666560
1403636952451666432
1403636952501666560
1403636952551666432
1403636952601666560
1403636952651666432
1403636952701666560
1403636952751666432
1403636952801666560
1403636952851666432
1403636952901666560
1403636952951666432
1403636953001666560
1403636953051666432
1403636953101666560
1403636953151666432
1403636953201666560
1403636953251666432
1403636953301666560
1403636953351666432
1403636953401666560
1403636953451666432
1403636953501666560
1403636953551666432
1403636953601666560
1403636953651666432
1403636953701666560
1403636953751666432
1403636953801666560
1403636953851666432
1403636953901666560
1403636953951666432
1403636954001666560
1403636954051666432
1403636954101666560
1403636954151666432
1403636954201666560
1403636954251666432
1403636954301666560
1403636954351666432
1403636954401666560
1403636954451666432
1403636954501666560
1403636954551666432
1403636954601666560
1403636954651666432
1403636954701666560
1403636954751666432
1403636954801666560
1403636954851666432
1403636954901666560
1403636954951666432
1403636955001666560
1403636955051666432
1403636955101666560
1403636955151666432
1403636955201666560
1403636955251666432
1403636955301666560
1403636955351666432
1403636955401666560
1403636955451666432
1403636955501666560
1403636955551666432
1403636955601666560
1403636955651666432
1403636955701666560
1403636955751666432
1403636955801666560
1403636955851666432
1403636955901666560
1403636955951666432
1403636956001666560
1403636956051666432
1403636956101666560
1403636956151666432
1403636956201666560
1403636956251666432
1403636956301666560
1403636956351666432
1403636956401666560
1403636956451666432
1403636956501666560
1403636956551666432
1403636956601666560
1403636956651666432
1403636956701666560
1403636956751666432
1403636956801666560
1403636956851666432
1403636956901666560
1403636956951666432
1403636957001666560
1403636957051666432
1403636957101666560
1403636957151666432
1403636957201666560
1403636957251666432
1403636957301666560
1403636957351666432
1403636957401666560
1403636957451666432
1403636957501666560
1403636957551666432
1403636957601666560
1403636957651666432
1403636957701666560
1403636957751666432
1403636957801666560
1403636957851666432
1403636957901666560
1403636957951666432
1403636958001666560
1403636958051666432
1403636958101666560
1403636958151666432
1403636958201666560
1403636958251666432
1403636958301666560
1403636958351666432
1403636958401666560
1403636958451666432
1403636958501666560
1403636958551666432
1403636958601666560
1403636958651666432
1403636958701666560
1403636958751666432
1403636958801666560
1403636958851666432
1403636958901666560
1403636958951666432
1403636959001666560
1403636959051666432
1403636959101666560
1403636959151666432
1403636959201666560
1403636959251666432
1403636959301666560
1403636959351666432
1403636959401666560
1403636959451666432
1403636959501666560
1403636959551666432
1403636959601666560
1403636959651666432
1403636959701666560
1403636959751666432
1403636959801666560
1403636959851666432
1403636959901666560
1403636959951666432
1403636960001666560
1403636960051666432
1403636960101666560
1403636960151666432
1403636960201666560
1403636960251666432
1403636960301666560
1403636960351666432
1403636960401666560
1403636960451666432
1403636960501666560
1403636960551666432
1403636960601666560
1403636960651666432
1403636960701666560
1403636960751666432
1403636960801666560
1403636960851666432
1403636960901666560
1403636960951666432
1403636961001666560
1403636961051666432
1403636961101666560
1403636961151666432
1403636961201666560
1403636961251666432
1403636961301666560
1403636961351666432
1403636961401666560
1403636961451666432
1403636961501666560
1403636961551666432
1403636961601666560
1403636961651666432
1403636961701666560
1403636961751666432
1403636961801666560
1403636961851666432
1403636961901666560
1403636961951666432
1403636962001666560
1403636962051666432
1403636962101666560
1403636962151666432
1403636962201666560
1403636962251666432
1403636962301666560
1403636962351666432
1403636962401666560
1403636962451666432
1403636962501666560
1403636962551666432
1403636962601666560
1403636962651666432
1403636962701666560
1403636962751666432
1403636962801666560
1403636962851666432
1403636962901666560
1403636962951666432
1403636963001666560
1403636963051666432
1403636963101666560
1403636963151666432
1403636963201666560
1403636963251666432
1403636963301666560
1403636963351666432
1403636963401666560
1403636963451666432
1403636963501666560
1403636963551666432
1403636963601666560
1403636963651666432
1403636963701666560
1403636963751666432
1403636963801666560
1403636963851666432
1403636963901666560
1403636963951666432
1403636964001666560
1403636964051666432
1403636964101666560
1403636964151666432
1403636964201666560
1403636964251666432
1403636964301666560
1403636964351666432
1403636964401666560
1403636964451666432
1403636964501666560
1403636964551666432
1403636964601666560
1403636964651666432
1403636964701666560
1403636964751666432
1403636964801666560
1403636964851666432
1403636964901666560
1403636964951666432
1403636965001666560
1403636965051666432
1403636965101666560
1403636965151666432
1403636965201666560
1403636965251666432
1403636965301666560
1403636965351666432
1403636965401666560
1403636965451666432
1403636965501666560
1403636965551666432
1403636965601666560
1403636965651666432
1403636965701666560
1403636965751666432
1403636965801666560
1403636965851666432
1403636965901666560
1403636965951666432
1403636966001666560
1403636966051666432
1403636966101666560
1403636966151666432
1403636966201666560
1403636966251666432
1403636966301666560
1403636966351666432
1403636966401666560
1403636966451666432
1403636966501666560
1403636966551666432
1403636966601666560
1403636966651666432
1403636966701666560
1403636966751666432
1403636966801666560
1403636966851666432
1403636966901666560
1403636966951666432
1403636967001666560
1403636967051666432
1403636967101666560
1403636967151666432
1403636967201666560
1403636967251666432
1403636967301666560
1403636967351666432
1403636967401666560
1403636967451666432
1403636967501666560
1403636967551666432
1403636967601666560
1403636967651666432
1403636967701666560
1403636967751666432
1403636967801666560
1403636967851666432
1403636967901666560
1403636967951666432
1403636968001666560
1403636968051666432
1403636968101666560
1403636968151666432
1403636968201666560
1403636968251666432
1403636968301666560
1403636968351666432
1403636968401666560
1403636968451666432
1403636968501666560
1403636968551666432
1403636968601666560
1403636968651666432
1403636968701666560
1403636968751666432
1403636968801666560
1403636968851666432
1403636968901666560
1403636968951666432
1403636969001666560
1403636969051666432
1403636969101666560
1403636969151666432
1403636969201666560
1403636969251666432
1403636969301666560
1403636969351666432
1403636969401666560
1403636969451666432
1403636969501666560
1403636969551666432
1403636969601666560
1403636969651666432
1403636969701666560
1403636969751666432
1403636969801666560
1403636969851666432
1403636969901666560
1403636969951666432
1403636970001666560
1403636970051666432
1403636970101666560
1403636970151666432
1403636970201666560
1403636970251666432
1403636970301666560
1403636970351666432
1403636970401666560
1403636970451666432
1403636970501666560
1403636970551666432
1403636970601666560
1403636970651666432
1403636970701666560
1403636970751666432
1403636970801666560
1403636970851666432
1403636970901666560
1403636970951666432
1403636971001666560
1403636971051666432
1403636971101666560
1403636971151666432
1403636971201666560
1403636971251666432
1403636971301666560
1403636971351666432
1403636971401666560
1403636971451666432
1403636971501666560
1403636971551666432
1403636971601666560
1403636971651666432
1403636971701666560
1403636971751666432
1403636971801666560
1403636971851666432
1403636971901666560
1403636971951666432
1403636972001666560
1403636972051666432
1403636972101666560
1403636972151666432
1403636972201666560
1403636972251666432
1403636972301666560
1403636972351666432
1403636972401666560
1403636972451666432
1403636972501666560
1403636972551666432
1403636972601666560
1403636972651666432
1403636972701666560
1403636972751666432
1403636972801666560
1403636972851666432
1403636972901666560
1403636972951666432
1403636973001666560
1403636973051666432
1403636973101666560
1403636973151666432
1403636973201666560
1403636973251666432
1403636973301666560
1403636973351666432
1403636973401666560
1403636973451666432
1403636973501666560
1403636973551666432
1403636973601666560
1403636973651666432
1403636973701666560
1403636973751666432
1403636973801666560
1403636973851666432
1403636973901666560
1403636973951666432
1403636974001666560
1403636974051666432
1403636974101666560
1403636974151666432
1403636974201666560
1403636974251666432
1403636974301666560
1403636974351666432
1403636974401666560
1403636974451666432
1403636974501666560
1403636974551666432
1403636974601666560
1403636974651666432
1403636974701666560
1403636974751666432
1403636974801666560
1403636974851666432
1403636974901666560
1403636974951666432
1403636975001666560
1403636975051666432
1403636975101666560
1403636975151666432
1403636975201666560
1403636975251666432
1403636975301666560
1403636975351666432
1403636975401666560
1403636975451666432
1403636975501666560
1403636975551666432
1403636975601666560
1403636975651666432
1403636975701666560
1403636975751666432
1403636975801666560
1403636975851666432
1403636975901666560
1403636975951666432
1403636976001666560
1403636976051666432
1403636976101666560
1403636976151666432
1403636976201666560
1403636976251666432
1403636976301666560
1403636976351666432
1403636976401666560
1403636976451666432
1403636976501666560
1403636976551666432
1403636976601666560
1403636976651666432
1403636976701666560
1403636976751666432
1403636976801666560
1403636976851666432
1403636976901666560
1403636976951666432
1403636977001666560
1403636977051666432
1403636977101666560
1403636977151666432
1403636977201666560
1403636977251666432
1403636977301666560
1403636977351666432
1403636977401666560
1403636977451666432
1403636977501666560
1403636977551666432
1403636977601666560
1403636977651666432
1403636977701666560
1403636977751666432
1403636977801666560
1403636977851666432
1403636977901666560
1403636977951666432
1403636978001666560
1403636978051666432
1403636978101666560
1403636978151666432
1403636978201666560
1403636978251666432
1403636978301666560
1403636978351666432
1403636978401666560
1403636978451666432
1403636978501666560
1403636978551666432
1403636978601666560
1403636978651666432
1403636978701666560
1403636978751666432
1403636978801666560
1403636978851666432
1403636978901666560
1403636978951666432
1403636979001666560
1403636979051666432
1403636979101666560
1403636979151666432
1403636979201666560
1403636979251666432
1403636979301666560
1403636979351666432
1403636979401666560
1403636979451666432
1403636979501666560
1403636979551666432
1403636979601666560
1403636979651666432
1403636979701666560
1403636979751666432
1403636979801666560
1403636979851666432
1403636979901666560
1403636979951666432
1403636980001666560
1403636980051666432
1403636980101666560
1403636980151666432
1403636980201666560
1403636980251666432
1403636980301666560
1403636980351666432
1403636980401666560
1403636980451666432
1403636980501666560
1403636980551666432
1403636980601666560
1403636980651666432
1403636980701666560
1403636980751666432
1403636980801666560
1403636980851666432
1403636980901666560
1403636980951666432
1403636981001666560
1403636981051666432
1403636981101666560
1403636981151666432
1403636981201666560
1403636981251666432
1403636981301666560
1403636981351666432
1403636981401666560
1403636981451666432
1403636981501666560
1403636981551666432
1403636981601666560
1403636981651666432
1403636981701666560
1403636981751666432
1403636981801666560
1403636981851666432
1403636981901666560
1403636981951666432
1403636982001666560
1403636982051666432
1403636982101666560
1403636982151666432
1403636982201666560
1403636982251666432
1403636982301666560
1403636982351666432
1403636982401666560
1403636982451666432
1403636982501666560
1403636982551666432
1403636982601666560
1403636982651666432
1403636982701666560
1403636982751666432
1403636982801666560
1403636982851666432
1403636982901666560
1403636982951666432
1403636983001666560
1403636983051666432
1403636983101666560
1403636983151666432
1403636983201666560
1403636983251666432
1403636983301666560
1403636983351666432
1403636983401666560
1403636983451666432
1403636983501666560
1403636983551666432
1403636983601666560
1403636983651666432
1403636983701666560
1403636983751666432
1403636983801666560
1403636983851666432
1403636983901666560
1403636983951666432
1403636984001666560
1403636984051666432
1403636984101666560
1403636984151666432
1403636984201666560
1403636984251666432
1403636984301666560
1403636984351666432
1403636984401666560
1403636984451666432
1403636984501666560
1403636984551666432
1403636984601666560
1403636984651666432
1403636984701666560
1403636984751666432
1403636984801666560
1403636984851666432
1403636984901666560
1403636984951666432
1403636985001666560
1403636985051666432
1403636985101666560
1403636985151666432
1403636985201666560
1403636985251666432
1403636985301666560
1403636985351666432
1403636985401666560
1403636985451666432
1403636985501666560
1403636985551666432
1403636985601666560
1403636985651666432
1403636985701666560
1403636985751666432
1403636985801666560
1403636985851666432
1403636985901666560
1403636985951666432
1403636986001666560
1403636986051666432
1403636986101666560
1403636986151666432
1403636986201666560
1403636986251666432
1403636986301666560
1403636986351666432
1403636986401666560
1403636986451666432
1403636986501666560
1403636986551666432
1403636986601666560
1403636986651666432
1403636986701666560
1403636986751666432
1403636986801666560
1403636986851666432
1403636986901666560
1403636986951666432
1403636987001666560
1403636987051666432
1403636987101666560
1403636987151666432
1403636987201666560
1403636987251666432
1403636987301666560
1403636987351666432
1403636987401666560
1403636987451666432
1403636987501666560
1403636987551666432
1403636987601666560
1403636987651666432
1403636987701666560
1403636987751666432
1403636987801666560
1403636987851666432
1403636987901666560
1403636987951666432
1403636988001666560
1403636988051666432
1403636988101666560
1403636988151666432
1403636988201666560
1403636988251666432
1403636988301666560
1403636988351666432
1403636988401666560
1403636988451666432
1403636988501666560
1403636988551666432
1403636988601666560
1403636988651666432
1403636988701666560
1403636988751666432
1403636988801666560
1403636988851666432
1403636988901666560
1403636988951666432
1403636989001666560
1403636989051666432
1403636989101666560
1403636989151666432
1403636989201666560
1403636989251666432
1403636989301666560
1403636989351666432
1403636989401666560
1403636989451666432
1403636989501666560
1403636989551666432
1403636989601666560
1403636989651666432
1403636989701666560
1403636989751666432
1403636989801666560
1403636989851666432
1403636989901666560
1403636989951666432
1403636990001666560
1403636990051666432
1403636990101666560
1403636990151666432
1403636990201666560
1403636990251666432
1403636990301666560
1403636990351666432
1403636990401666560
1403636990451666432
1403636990501666560
1403636990551666432
1403636990601666560
1403636990651666432
1403636990701666560
1403636990751666432
1403636990801666560
1403636990851666432
1403636990901666560
1403636990951666432
1403636991001666560
1403636991051666432
1403636991101666560
1403636991151666432
1403636991201666560
1403636991251666432
1403636991301666560
1403636991351666432
1403636991401666560
1403636991451666432
1403636991501666560
1403636991551666432
1403636991601666560
1403636991651666432
1403636991701666560
1403636991751666432
1403636991801666560
1403636991851666432
1403636991901666560
1403636991951666432
1403636992001666560
1403636992051666432
1403636992101666560
1403636992151666432
1403636992201666560
1403636992251666432
1403636992301666560
1403636992351666432
1403636992401666560
1403636992451666432
1403636992501666560
1403636992551666432
1403636992601666560
1403636992651666432
1403636992701666560
1403636992751666432
1403636992801666560
1403636992851666432
1403636992901666560
1403636992951666432
1403636993001666560
1403636993051666432
1403636993101666560
1403636993151666432
1403636993201666560
1403636993251666432
1403636993301666560
1403636993351666432
1403636993401666560
1403636993451666432
1403636993501666560
1403636993551666432
1403636993601666560
1403636993651666432
1403636993701666560
1403636993751666432
1403636993801666560
1403636993851666432
1403636993901666560
1403636993951666432
1403636994001666560
1403636994051666432
1403636994101666560
1403636994151666432
1403636994201666560
1403636994251666432
1403636994301666560
1403636994351666432
1403636994401666560
1403636994451666432
1403636994501666560
1403636994551666432
1403636994601666560
1403636994651666432
1403636994701666560
1403636994751666432
1403636994801666560
1403636994851666432
1403636994901666560
1403636994951666432
1403636995001666560
1403636995051666432
1403636995101666560
1403636995151666432
1403636995201666560
1403636995251666432
1403636995301666560
1403636995351666432
1403636995401666560
1403636995451666432
1403636995501666560
1403636995551666432
1403636995601666560
1403636995651666432
1403636995701666560
1403636995751666432
1403636995801666560
1403636995851666432
1403636995901666560
1403636995951666432
1403636996001666560
1403636996051666432
1403636996101666560
1403636996151666432
1403636996201666560
1403636996251666432
1403636996301666560
1403636996351666432
1403636996401666560
1403636996451666432
1403636996501666560
1403636996551666432
1403636996601666560
1403636996651666432
1403636996701666560
1403636996751666432
1403636996801666560
1403636996851666432
1403636996901666560
1403636996951666432
1403636997001666560
1403636997051666432
1403636997101666560
1403636997151666432
1403636997201666560
1403636997251666432
1403636997301666560
1403636997351666432
1403636997401666560
1403636997451666432
1403636997501666560
1403636997551666432
1403636997601666560
1403636997651666432
1403636997701666560
1403636997751666432
1403636997801666560
1403636997851666432
1403636997901666560
1403636997951666432
1403636998001666560
1403636998051666432
1403636998101666560
1403636998151666432
1403636998201666560
1403636998251666432
1403636998301666560
1403636998351666432
1403636998401666560
1403636998451666432
1403636998501666560
1403636998551666432
1403636998601666560
1403636998651666432
1403636998701666560
1403636998751666432
1403636998801666560
1403636998851666432
1403636998901666560
1403636998951666432
1403636999001666560
1403636999051666432
1403636999101666560
1403636999151666432
1403636999201666560
1403636999251666432
1403636999301666560
1403636999351666432
1403636999401666560
1403636999451666432
1403636999501666560
1403636999551666432
1403636999601666560
1403636999651666432
1403636999701666560
1403636999751666432
1403636999801666560
1403636999851666432
1403636999901666560
1403636999951666432
1403637000001666560
1403637000051666432
1403637000101666560
1403637000151666432
1403637000201666560
1403637000251666432
1403637000301666560
1403637000351666432
1403637000401666560
1403637000451666432
1403637000501666560
1403637000551666432
1403637000601666560
1403637000651666432
1403637000701666560
1403637000751666432
1403637000801666560
1403637000851666432
1403637000901666560
1403637000951666432
1403637001001666560
1403637001051666432
1403637001101666560
1403637001151666432
1403637001201666560
1403637001251666432
1403637001301666560
1403637001351666432
1403637001401666560
1403637001451666432
1403637001501666560
1403637001551666432
1403637001601666560
1403637001651666432
1403637001701666560
1403637001751666432
1403637001801666560
1403637001851666432
1403637001901666560
1403637001951666432
1403637002001666560
1403637002051666432
1403637002101666560
1403637002151666432
1403637002201666560
1403637002251666432
1403637002301666560
1403637002351666432
1403637002401666560
1403637002451666432
1403637002501666560
1403637002551666432
1403637002601666560
1403637002651666432
1403637002701666560
1403637002751666432
1403637002801666560
1403637002851666432
1403637002901666560
1403637002951666432
1403637003001666560
1403637003051666432
1403637003101666560
1403637003151666432
1403637003201666560
1403637003251666432
1403637003301666560
1403637003351666432
1403637003401666560
1403637003451666432
1403637003501666560
1403637003551666432
1403637003601666560
1403637003651666432
1403637003701666560
1403637003751666432
1403637003801666560
1403637003851666432
1403637003901666560
1403637003951666432
1403637004001666560
1403637004051666432
1403637004101666560
1403637004151666432
1403637004201666560
1403637004251666432
1403637004301666560
1403637004351666432
1403637004401666560
1403637004451666432
1403637004501666560
1403637004551666432
1403637004601666560
1403637004651666432
1403637004701666560
1403637004751666432
1403637004801666560
1403637004851666432
1403637004901666560
1403637004951666432
1403637005001666560
1403637005051666432
1403637005101666560
1403637005151666432
1403637005201666560
1403637005251666432
1403637005301666560
1403637005351666432
1403637005401666560
1403637005451666432
1403637005501666560
1403637005551666432
1403637005601666560
1403637005651666432
1403637005701666560
1403637005751666432
1403637005801666560
1403637005851666432
1403637005901666560
1403637005951666432
1403637006001666560
1403637006051666432
1403637006101666560
1403637006151666432
1403637006201666560
1403637006251666432
1403637006301666560
1403637006351666432
1403637006401666560
1403637006451666432
1403637006501666560
1403637006551666432
1403637006601666560
1403637006651666432
1403637006701666560
1403637006751666432
1403637006801666560
1403637006851666432
1403637006901666560
1403637006951666432
1403637007001666560
1403637007051666432
1403637007101666560
1403637007151666432
1403637007201666560
1403637007251666432
1403637007301666560
1403637007351666432
1403637007401666560
1403637007451666432
1403637007501666560
1403637007551666432
1403637007601666560
1403637007651666432
1403637007701666560
1403637007751666432
1403637007801666560
1403637007851666432
1403637007901666560
1403637007951666432
1403637008001666560
1403637008051666432
1403637008101666560
1403637008151666432
1403637008201666560
1403637008251666432
1403637008301666560
1403637008351666432
1403637008401666560
1403637008451666432
1403637008501666560
1403637008551666432
1403637008601666560
1403637008651666432
1403637008701666560
1403637008751666432
1403637008801666560
1403637008851666432
1403637008901666560
1403637008951666432
1403637009001666560
1403637009051666432
1403637009101666560
1403637009151666432
1403637009201666560
1403637009251666432
1403637009301666560
1403637009351666432
1403637009401666560
1403637009451666432
1403637009501666560
1403637009551666432
1403637009601666560
1403637009651666432
1403637009701666560
1403637009751666432
1403637009801666560
1403637009851666432
1403637009901666560
1403637009951666432
1403637010001666560
1403637010051666432
1403637010101666560
1403637010151666432
1403637010201666560
1403637010251666432
1403637010301666560
1403637010351666432
1403637010401666560
1403637010451666432
1403637010501666560
1403637010551666432
1403637010601666560
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/MH03.txt
================================================
1403637130538319104
1403637130588318976
1403637130638319104
1403637130688318976
1403637130738319104
1403637130788318976
1403637130838319104
1403637130888318976
1403637130938319104
1403637130988318976
1403637131038319104
1403637131088318976
1403637131138319104
1403637131188318976
1403637131238319104
1403637131288318976
1403637131338319104
1403637131388318976
1403637131438319104
1403637131488318976
1403637131538319104
1403637131588318976
1403637131638319104
1403637131688318976
1403637131738319104
1403637131788318976
1403637131838319104
1403637131888318976
1403637131938319104
1403637131988318976
1403637132038319104
1403637132088318976
1403637132138319104
1403637132188318976
1403637132238319104
1403637132288318976
1403637132338319104
1403637132388318976
1403637132438319104
1403637132488318976
1403637132538319104
1403637132588318976
1403637132638319104
1403637132688318976
1403637132738319104
1403637132788318976
1403637132838319104
1403637132888318976
1403637132938319104
1403637132988318976
1403637133038319104
1403637133088318976
1403637133138319104
1403637133188318976
1403637133238319104
1403637133288318976
1403637133338319104
1403637133388318976
1403637133438319104
1403637133488318976
1403637133538319104
1403637133588318976
1403637133638319104
1403637133688318976
1403637133738319104
1403637133788318976
1403637133838319104
1403637133888318976
1403637133938319104
1403637133988318976
1403637134038319104
1403637134088318976
1403637134138319104
1403637134188318976
1403637134238319104
1403637134288318976
1403637134338319104
1403637134388318976
1403637134438319104
1403637134488318976
1403637134538319104
1403637134588318976
1403637134638319104
1403637134688318976
1403637134738319104
1403637134788318976
1403637134838319104
1403637134888318976
1403637134938319104
1403637134988318976
1403637135038319104
1403637135088318976
1403637135138319104
1403637135188318976
1403637135238319104
1403637135288318976
1403637135338319104
1403637135388318976
1403637135438319104
1403637135488318976
1403637135538319104
1403637135588318976
1403637135638319104
1403637135688318976
1403637135738319104
1403637135788318976
1403637135838319104
1403637135888318976
1403637135938319104
1403637135988318976
1403637136038319104
1403637136088318976
1403637136138319104
1403637136188318976
1403637136238319104
1403637136288318976
1403637136338319104
1403637136388318976
1403637136438319104
1403637136488318976
1403637136538319104
1403637136588318976
1403637136638319104
1403637136688318976
1403637136738319104
1403637136788318976
1403637136838319104
1403637136888318976
1403637136938319104
1403637136988318976
1403637137038319104
1403637137088318976
1403637137138319104
1403637137188318976
1403637137238319104
1403637137288318976
1403637137338319104
1403637137388318976
1403637137438319104
1403637137488318976
1403637137538319104
1403637137588318976
1403637137638319104
1403637137688318976
1403637137738319104
1403637137788318976
1403637137838319104
1403637137888318976
1403637137938319104
1403637137988318976
1403637138038319104
1403637138088318976
1403637138138319104
1403637138188318976
1403637138238319104
1403637138288318976
1403637138338319104
1403637138388318976
1403637138438319104
1403637138488318976
1403637138538319104
1403637138588318976
1403637138638319104
1403637138688318976
1403637138738319104
1403637138788318976
1403637138838319104
1403637138888318976
1403637138938319104
1403637138988318976
1403637139038319104
1403637139088318976
1403637139138319104
1403637139188318976
1403637139238319104
1403637139288318976
1403637139338319104
1403637139388318976
1403637139438319104
1403637139488318976
1403637139538319104
1403637139588318976
1403637139638319104
1403637139688318976
1403637139738319104
1403637139788318976
1403637139838319104
1403637139888318976
1403637139938319104
1403637139988318976
1403637140038319104
1403637140088318976
1403637140138319104
1403637140188318976
1403637140238319104
1403637140288318976
1403637140338319104
1403637140388318976
1403637140438319104
1403637140488318976
1403637140538319104
1403637140588318976
1403637140638319104
1403637140688318976
1403637140738319104
1403637140788318976
1403637140838319104
1403637140888318976
1403637140938319104
1403637140988318976
1403637141038319104
1403637141088318976
1403637141138319104
1403637141188318976
1403637141238319104
1403637141288318976
1403637141338319104
1403637141388318976
1403637141438319104
1403637141488318976
1403637141538319104
1403637141588318976
1403637141638319104
1403637141688318976
1403637141738319104
1403637141788318976
1403637141838319104
1403637141888318976
1403637141938319104
1403637141988318976
1403637142038319104
1403637142088318976
1403637142138319104
1403637142188318976
1403637142238319104
1403637142288318976
1403637142338319104
1403637142388318976
1403637142438319104
1403637142488318976
1403637142538319104
1403637142588318976
1403637142638319104
1403637142688318976
1403637142738319104
1403637142788318976
1403637142838319104
1403637142888318976
1403637142938319104
1403637142988318976
1403637143038319104
1403637143088318976
1403637143138319104
1403637143188318976
1403637143238319104
1403637143288318976
1403637143338319104
1403637143388318976
1403637143438319104
1403637143488318976
1403637143538319104
1403637143588318976
1403637143638319104
1403637143688318976
1403637143738319104
1403637143788318976
1403637143838319104
1403637143888318976
1403637143938319104
1403637143988318976
1403637144038319104
1403637144088318976
1403637144138319104
1403637144188318976
1403637144238319104
1403637144288318976
1403637144338319104
1403637144388318976
1403637144438319104
1403637144488318976
1403637144538319104
1403637144588318976
1403637144638319104
1403637144688318976
1403637144738319104
1403637144788318976
1403637144838319104
1403637144888318976
1403637144938319104
1403637144988318976
1403637145038319104
1403637145088318976
1403637145138319104
1403637145188318976
1403637145238319104
1403637145288318976
1403637145338319104
1403637145388318976
1403637145438319104
1403637145488318976
1403637145538319104
1403637145588318976
1403637145638319104
1403637145688318976
1403637145738319104
1403637145788318976
1403637145838319104
1403637145888318976
1403637145938319104
1403637145988318976
1403637146038319104
1403637146088318976
1403637146138319104
1403637146188318976
1403637146238319104
1403637146288318976
1403637146338319104
1403637146388318976
1403637146438319104
1403637146488318976
1403637146538319104
1403637146588318976
1403637146638319104
1403637146688318976
1403637146738319104
1403637146788318976
1403637146838319104
1403637146888318976
1403637146938319104
1403637146988318976
1403637147038319104
1403637147088318976
1403637147138319104
1403637147188318976
1403637147238319104
1403637147288318976
1403637147338319104
1403637147388318976
1403637147438319104
1403637147488318976
1403637147538319104
1403637147588318976
1403637147638319104
1403637147688318976
1403637147738319104
1403637147788318976
1403637147838319104
1403637147888318976
1403637147938319104
1403637147988318976
1403637148038319104
1403637148088318976
1403637148138319104
1403637148188318976
1403637148238319104
1403637148288318976
1403637148338319104
1403637148388318976
1403637148438319104
1403637148488318976
1403637148538319104
1403637148588318976
1403637148638319104
1403637148688318976
1403637148738319104
1403637148788318976
1403637148838319104
1403637148888318976
1403637148938319104
1403637148988318976
1403637149038319104
1403637149088318976
1403637149138319104
1403637149188318976
1403637149238319104
1403637149288318976
1403637149338319104
1403637149388318976
1403637149438319104
1403637149488318976
1403637149538319104
1403637149588318976
1403637149638319104
1403637149688318976
1403637149738319104
1403637149788318976
1403637149838319104
1403637149888318976
1403637149938319104
1403637149988318976
1403637150038319104
1403637150088318976
1403637150138319104
1403637150188318976
1403637150238319104
1403637150288318976
1403637150338319104
1403637150388318976
1403637150438319104
1403637150488318976
1403637150538319104
1403637150588318976
1403637150638319104
1403637150688318976
1403637150738319104
1403637150788318976
1403637150838319104
1403637150888318976
1403637150938319104
1403637150988318976
1403637151038319104
1403637151088318976
1403637151138319104
1403637151188318976
1403637151238319104
1403637151288318976
1403637151338319104
1403637151388318976
1403637151438319104
1403637151488318976
1403637151538319104
1403637151588318976
1403637151638319104
1403637151688318976
1403637151738319104
1403637151788318976
1403637151838319104
1403637151888318976
1403637151938319104
1403637151988318976
1403637152038319104
1403637152088318976
1403637152138319104
1403637152188318976
1403637152238319104
1403637152288318976
1403637152338319104
1403637152388318976
1403637152438319104
1403637152488318976
1403637152538319104
1403637152588318976
1403637152638319104
1403637152688318976
1403637152738319104
1403637152788318976
1403637152838319104
1403637152888318976
1403637152938319104
1403637152988318976
1403637153038319104
1403637153088318976
1403637153138319104
1403637153188318976
1403637153238319104
1403637153288318976
1403637153338319104
1403637153388318976
1403637153438319104
1403637153488318976
1403637153538319104
1403637153588318976
1403637153638319104
1403637153688318976
1403637153738319104
1403637153788318976
1403637153838319104
1403637153888318976
1403637153938319104
1403637153988318976
1403637154038319104
1403637154088318976
1403637154138319104
1403637154188318976
1403637154238319104
1403637154288318976
1403637154338319104
1403637154388318976
1403637154438319104
1403637154488318976
1403637154538319104
1403637154588318976
1403637154638319104
1403637154688318976
1403637154738319104
1403637154788318976
1403637154838319104
1403637154888318976
1403637154938319104
1403637154988318976
1403637155038319104
1403637155088318976
1403637155138319104
1403637155188318976
1403637155238319104
1403637155288318976
1403637155338319104
1403637155388318976
1403637155438319104
1403637155488318976
1403637155538319104
1403637155588318976
1403637155638319104
1403637155688318976
1403637155738319104
1403637155788318976
1403637155838319104
1403637155888318976
1403637155938319104
1403637155988318976
1403637156038319104
1403637156088318976
1403637156138319104
1403637156188318976
1403637156238319104
1403637156288318976
1403637156338319104
1403637156388318976
1403637156438319104
1403637156488318976
1403637156538319104
1403637156588318976
1403637156638319104
1403637156688318976
1403637156738319104
1403637156788318976
1403637156838319104
1403637156888318976
1403637156938319104
1403637156988318976
1403637157038319104
1403637157088318976
1403637157138319104
1403637157188318976
1403637157238319104
1403637157288318976
1403637157338319104
1403637157388318976
1403637157438319104
1403637157488318976
1403637157538319104
1403637157588318976
1403637157638319104
1403637157688318976
1403637157738319104
1403637157788318976
1403637157838319104
1403637157888318976
1403637157938319104
1403637157988318976
1403637158038319104
1403637158088318976
1403637158138319104
1403637158188318976
1403637158238319104
1403637158288318976
1403637158338319104
1403637158388318976
1403637158438319104
1403637158488318976
1403637158538319104
1403637158588318976
1403637158638319104
1403637158688318976
1403637158738319104
1403637158788318976
1403637158838319104
1403637158888318976
1403637158938319104
1403637158988318976
1403637159038319104
1403637159088318976
1403637159138319104
1403637159188318976
1403637159238319104
1403637159288318976
1403637159338319104
1403637159388318976
1403637159438319104
1403637159488318976
1403637159538319104
1403637159588318976
1403637159638319104
1403637159688318976
1403637159738319104
1403637159788318976
1403637159838319104
1403637159888318976
1403637159938319104
1403637159988318976
1403637160038319104
1403637160088318976
1403637160138319104
1403637160188318976
1403637160238319104
1403637160288318976
1403637160338319104
1403637160388318976
1403637160438319104
1403637160488318976
1403637160538319104
1403637160588318976
1403637160638319104
1403637160688318976
1403637160738319104
1403637160788318976
1403637160838319104
1403637160888318976
1403637160938319104
1403637160988318976
1403637161038319104
1403637161088318976
1403637161138319104
1403637161188318976
1403637161238319104
1403637161288318976
1403637161338319104
1403637161388318976
1403637161438319104
1403637161488318976
1403637161538319104
1403637161588318976
1403637161638319104
1403637161688318976
1403637161738319104
1403637161788318976
1403637161838319104
1403637161888318976
1403637161938319104
1403637161988318976
1403637162038319104
1403637162088318976
1403637162138319104
1403637162188318976
1403637162238319104
1403637162288318976
1403637162338319104
1403637162388318976
1403637162438319104
1403637162488318976
1403637162538319104
1403637162588318976
1403637162638319104
1403637162688318976
1403637162738319104
1403637162788318976
1403637162838319104
1403637162888318976
1403637162938319104
1403637162988318976
1403637163038319104
1403637163088318976
1403637163138319104
1403637163188318976
1403637163238319104
1403637163288318976
1403637163338319104
1403637163388318976
1403637163438319104
1403637163488318976
1403637163538319104
1403637163588318976
1403637163638319104
1403637163688318976
1403637163738319104
1403637163788318976
1403637163838319104
1403637163888318976
1403637163938319104
1403637163988318976
1403637164038319104
1403637164088318976
1403637164138319104
1403637164188318976
1403637164238319104
1403637164288318976
1403637164338319104
1403637164388318976
1403637164438319104
1403637164488318976
1403637164538319104
1403637164588318976
1403637164638319104
1403637164688318976
1403637164738319104
1403637164788318976
1403637164838319104
1403637164888318976
1403637164938319104
1403637164988318976
1403637165038319104
1403637165088318976
1403637165138319104
1403637165188318976
1403637165238319104
1403637165288318976
1403637165338319104
1403637165388318976
1403637165438319104
1403637165488318976
1403637165538319104
1403637165588318976
1403637165638319104
1403637165688318976
1403637165738319104
1403637165788318976
1403637165838319104
1403637165888318976
1403637165938319104
1403637165988318976
1403637166038319104
1403637166088318976
1403637166138319104
1403637166188318976
1403637166238319104
1403637166288318976
1403637166338319104
1403637166388318976
1403637166438319104
1403637166488318976
1403637166538319104
1403637166588318976
1403637166638319104
1403637166688318976
1403637166738319104
1403637166788318976
1403637166838319104
1403637166888318976
1403637166938319104
1403637166988318976
1403637167038319104
1403637167088318976
1403637167138319104
1403637167188318976
1403637167238319104
1403637167288318976
1403637167338319104
1403637167388318976
1403637167438319104
1403637167488318976
1403637167538319104
1403637167588318976
1403637167638319104
1403637167688318976
1403637167738319104
1403637167788318976
1403637167838319104
1403637167888318976
1403637167938319104
1403637167988318976
1403637168038319104
1403637168088318976
1403637168138319104
1403637168188318976
1403637168238319104
1403637168288318976
1403637168338319104
1403637168388318976
1403637168438319104
1403637168488318976
1403637168538319104
1403637168588318976
1403637168638319104
1403637168688318976
1403637168738319104
1403637168788318976
1403637168838319104
1403637168888318976
1403637168938319104
1403637168988318976
1403637169038319104
1403637169088318976
1403637169138319104
1403637169188318976
1403637169238319104
1403637169288318976
1403637169338319104
1403637169388318976
1403637169438319104
1403637169488318976
1403637169538319104
1403637169588318976
1403637169638319104
1403637169688318976
1403637169738319104
1403637169788318976
1403637169838319104
1403637169888318976
1403637169938319104
1403637169988318976
1403637170038319104
1403637170088318976
1403637170138319104
1403637170188318976
1403637170238319104
1403637170288318976
1403637170338319104
1403637170388318976
1403637170438319104
1403637170488318976
1403637170538319104
1403637170588318976
1403637170638319104
1403637170688318976
1403637170738319104
1403637170788318976
1403637170838319104
1403637170888318976
1403637170938319104
1403637170988318976
1403637171038319104
1403637171088318976
1403637171138319104
1403637171188318976
1403637171238319104
1403637171288318976
1403637171338319104
1403637171388318976
1403637171438319104
1403637171488318976
1403637171538319104
1403637171588318976
1403637171638319104
1403637171688318976
1403637171738319104
1403637171788318976
1403637171838319104
1403637171888318976
1403637171938319104
1403637171988318976
1403637172038319104
1403637172088318976
1403637172138319104
1403637172188318976
1403637172238319104
1403637172288318976
1403637172338319104
1403637172388318976
1403637172438319104
1403637172488318976
1403637172538319104
1403637172588318976
1403637172638319104
1403637172688318976
1403637172738319104
1403637172788318976
1403637172838319104
1403637172888318976
1403637172938319104
1403637172988318976
1403637173038319104
1403637173088318976
1403637173138319104
1403637173188318976
1403637173238319104
1403637173288318976
1403637173338319104
1403637173388318976
1403637173438319104
1403637173488318976
1403637173538319104
1403637173588318976
1403637173638319104
1403637173688318976
1403637173738319104
1403637173788318976
1403637173838319104
1403637173888318976
1403637173938319104
1403637173988318976
1403637174038319104
1403637174088318976
1403637174138319104
1403637174188318976
1403637174238319104
1403637174288318976
1403637174338319104
1403637174388318976
1403637174438319104
1403637174488318976
1403637174538319104
1403637174588318976
1403637174638319104
1403637174688318976
1403637174738319104
1403637174788318976
1403637174838319104
1403637174888318976
1403637174938319104
1403637174988318976
1403637175038319104
1403637175088318976
1403637175138319104
1403637175188318976
1403637175238319104
1403637175288318976
1403637175338319104
1403637175388318976
1403637175438319104
1403637175488318976
1403637175538319104
1403637175588318976
1403637175638319104
1403637175688318976
1403637175738319104
1403637175788318976
1403637175838319104
1403637175888318976
1403637175938319104
1403637175988318976
1403637176038319104
1403637176088318976
1403637176138319104
1403637176188318976
1403637176238319104
1403637176288318976
1403637176338319104
1403637176388318976
1403637176438319104
1403637176488318976
1403637176538319104
1403637176588318976
1403637176638319104
1403637176688318976
1403637176738319104
1403637176788318976
1403637176838319104
1403637176888318976
1403637176938319104
1403637176988318976
1403637177038319104
1403637177088318976
1403637177138319104
1403637177188318976
1403637177238319104
1403637177288318976
1403637177338319104
1403637177388318976
1403637177438319104
1403637177488318976
1403637177538319104
1403637177588318976
1403637177638319104
1403637177688318976
1403637177738319104
1403637177788318976
1403637177838319104
1403637177888318976
1403637177938319104
1403637177988318976
1403637178038319104
1403637178088318976
1403637178138319104
1403637178188318976
1403637178238319104
1403637178288318976
1403637178338319104
1403637178388318976
1403637178438319104
1403637178488318976
1403637178538319104
1403637178588318976
1403637178638319104
1403637178688318976
1403637178738319104
1403637178788318976
1403637178838319104
1403637178888318976
1403637178938319104
1403637178988318976
1403637179038319104
1403637179088318976
1403637179138319104
1403637179188318976
1403637179238319104
1403637179288318976
1403637179338319104
1403637179388318976
1403637179438319104
1403637179488318976
1403637179538319104
1403637179588318976
1403637179638319104
1403637179688318976
1403637179738319104
1403637179788318976
1403637179838319104
1403637179888318976
1403637179938319104
1403637179988318976
1403637180038319104
1403637180088318976
1403637180138319104
1403637180188318976
1403637180238319104
1403637180288318976
1403637180338319104
1403637180388318976
1403637180438319104
1403637180488318976
1403637180538319104
1403637180588318976
1403637180638319104
1403637180688318976
1403637180738319104
1403637180788318976
1403637180838319104
1403637180888318976
1403637180938319104
1403637180988318976
1403637181038319104
1403637181088318976
1403637181138319104
1403637181188318976
1403637181238319104
1403637181288318976
1403637181338319104
1403637181388318976
1403637181438319104
1403637181488318976
1403637181538319104
1403637181588318976
1403637181638319104
1403637181688318976
1403637181738319104
1403637181788318976
1403637181838319104
1403637181888318976
1403637181938319104
1403637181988318976
1403637182038319104
1403637182088318976
1403637182138319104
1403637182188318976
1403637182238319104
1403637182288318976
1403637182338319104
1403637182388318976
1403637182438319104
1403637182488318976
1403637182538319104
1403637182588318976
1403637182638319104
1403637182688318976
1403637182738319104
1403637182788318976
1403637182838319104
1403637182888318976
1403637182938319104
1403637182988318976
1403637183038319104
1403637183088318976
1403637183138319104
1403637183188318976
1403637183238319104
1403637183288318976
1403637183338319104
1403637183388318976
1403637183438319104
1403637183488318976
1403637183538319104
1403637183588318976
1403637183638319104
1403637183688318976
1403637183738319104
1403637183788318976
1403637183838319104
1403637183888318976
1403637183938319104
1403637183988318976
1403637184038319104
1403637184088318976
1403637184138319104
1403637184188318976
1403637184238319104
1403637184288318976
1403637184338319104
1403637184388318976
1403637184438319104
1403637184488318976
1403637184538319104
1403637184588318976
1403637184638319104
1403637184688318976
1403637184738319104
1403637184788318976
1403637184838319104
1403637184888318976
1403637184938319104
1403637184988318976
1403637185038319104
1403637185088318976
1403637185138319104
1403637185188318976
1403637185238319104
1403637185288318976
1403637185338319104
1403637185388318976
1403637185438319104
1403637185488318976
1403637185538319104
1403637185588318976
1403637185638319104
1403637185688318976
1403637185738319104
1403637185788318976
1403637185838319104
1403637185888318976
1403637185938319104
1403637185988318976
1403637186038319104
1403637186088318976
1403637186138319104
1403637186188318976
1403637186238319104
1403637186288318976
1403637186338319104
1403637186388318976
1403637186438319104
1403637186488318976
1403637186538319104
1403637186588318976
1403637186638319104
1403637186688318976
1403637186738319104
1403637186788318976
1403637186838319104
1403637186888318976
1403637186938319104
1403637186988318976
1403637187038319104
1403637187088318976
1403637187138319104
1403637187188318976
1403637187238319104
1403637187288318976
1403637187338319104
1403637187388318976
1403637187438319104
1403637187488318976
1403637187538319104
1403637187588318976
1403637187638319104
1403637187688318976
1403637187738319104
1403637187788318976
1403637187838319104
1403637187888318976
1403637187938319104
1403637187988318976
1403637188038319104
1403637188088318976
1403637188138319104
1403637188188318976
1403637188238319104
1403637188288318976
1403637188338319104
1403637188388318976
1403637188438319104
1403637188488318976
1403637188538319104
1403637188588318976
1403637188638319104
1403637188688318976
1403637188738319104
1403637188788318976
1403637188838319104
1403637188888318976
1403637188938319104
1403637188988318976
1403637189038319104
1403637189088318976
1403637189138319104
1403637189188318976
1403637189238319104
1403637189288318976
1403637189338319104
1403637189388318976
1403637189438319104
1403637189488318976
1403637189538319104
1403637189588318976
1403637189638319104
1403637189688318976
1403637189738319104
1403637189788318976
1403637189838319104
1403637189888318976
1403637189938319104
1403637189988318976
1403637190038319104
1403637190088318976
1403637190138319104
1403637190188318976
1403637190238319104
1403637190288318976
1403637190338319104
1403637190388318976
1403637190438319104
1403637190488318976
1403637190538319104
1403637190588318976
1403637190638319104
1403637190688318976
1403637190738319104
1403637190788318976
1403637190838319104
1403637190888318976
1403637190938319104
1403637190988318976
1403637191038319104
1403637191088318976
1403637191138319104
1403637191188318976
1403637191238319104
1403637191288318976
1403637191338319104
1403637191388318976
1403637191438319104
1403637191488318976
1403637191538319104
1403637191588318976
1403637191638319104
1403637191688318976
1403637191738319104
1403637191788318976
1403637191838319104
1403637191888318976
1403637191938319104
1403637191988318976
1403637192038319104
1403637192088318976
1403637192138319104
1403637192188318976
1403637192238319104
1403637192288318976
1403637192338319104
1403637192388318976
1403637192438319104
1403637192488318976
1403637192538319104
1403637192588318976
1403637192638319104
1403637192688318976
1403637192738319104
1403637192788318976
1403637192838319104
1403637192888318976
1403637192938319104
1403637192988318976
1403637193038319104
1403637193088318976
1403637193138319104
1403637193188318976
1403637193238319104
1403637193288318976
1403637193338319104
1403637193388318976
1403637193438319104
1403637193488318976
1403637193538319104
1403637193588318976
1403637193638319104
1403637193688318976
1403637193738319104
1403637193788318976
1403637193838319104
1403637193888318976
1403637193938319104
1403637193988318976
1403637194038319104
1403637194088318976
1403637194138319104
1403637194188318976
1403637194238319104
1403637194288318976
1403637194338319104
1403637194388318976
1403637194438319104
1403637194488318976
1403637194538319104
1403637194588318976
1403637194638319104
1403637194688318976
1403637194738319104
1403637194788318976
1403637194838319104
1403637194888318976
1403637194938319104
1403637194988318976
1403637195038319104
1403637195088318976
1403637195138319104
1403637195188318976
1403637195238319104
1403637195288318976
1403637195338319104
1403637195388318976
1403637195438319104
1403637195488318976
1403637195538319104
1403637195588318976
1403637195638319104
1403637195688318976
1403637195738319104
1403637195788318976
1403637195838319104
1403637195888318976
1403637195938319104
1403637195988318976
1403637196038319104
1403637196088318976
1403637196138319104
1403637196188318976
1403637196238319104
1403637196288318976
1403637196338319104
1403637196388318976
1403637196438319104
1403637196488318976
1403637196538319104
1403637196588318976
1403637196638319104
1403637196688318976
1403637196738319104
1403637196788318976
1403637196838319104
1403637196888318976
1403637196938319104
1403637196988318976
1403637197038319104
1403637197088318976
1403637197138319104
1403637197188318976
1403637197238319104
1403637197288318976
1403637197338319104
1403637197388318976
1403637197438319104
1403637197488318976
1403637197538319104
1403637197588318976
1403637197638319104
1403637197688318976
1403637197738319104
1403637197788318976
1403637197838319104
1403637197888318976
1403637197938319104
1403637197988318976
1403637198038319104
1403637198088318976
1403637198138319104
1403637198188318976
1403637198238319104
1403637198288318976
1403637198338319104
1403637198388318976
1403637198438319104
1403637198488318976
1403637198538319104
1403637198588318976
1403637198638319104
1403637198688318976
1403637198738319104
1403637198788318976
1403637198838319104
1403637198888318976
1403637198938319104
1403637198988318976
1403637199038319104
1403637199088318976
1403637199138319104
1403637199188318976
1403637199238319104
1403637199288318976
1403637199338319104
1403637199388318976
1403637199438319104
1403637199488318976
1403637199538319104
1403637199588318976
1403637199638319104
1403637199688318976
1403637199738319104
1403637199788318976
1403637199838319104
1403637199888318976
1403637199938319104
1403637199988318976
1403637200038319104
1403637200088318976
1403637200138319104
1403637200188318976
1403637200238319104
1403637200288318976
1403637200338319104
1403637200388318976
1403637200438319104
1403637200488318976
1403637200538319104
1403637200588318976
1403637200638319104
1403637200688318976
1403637200738319104
1403637200788318976
1403637200838319104
1403637200888318976
1403637200938319104
1403637200988318976
1403637201038319104
1403637201088318976
1403637201138319104
1403637201188318976
1403637201238319104
1403637201288318976
1403637201338319104
1403637201388318976
1403637201438319104
1403637201488318976
1403637201538319104
1403637201588318976
1403637201638319104
1403637201688318976
1403637201738319104
1403637201788318976
1403637201838319104
1403637201888318976
1403637201938319104
1403637201988318976
1403637202038319104
1403637202088318976
1403637202138319104
1403637202188318976
1403637202238319104
1403637202288318976
1403637202338319104
1403637202388318976
1403637202438319104
1403637202488318976
1403637202538319104
1403637202588318976
1403637202638319104
1403637202688318976
1403637202738319104
1403637202788318976
1403637202838319104
1403637202888318976
1403637202938319104
1403637202988318976
1403637203038319104
1403637203088318976
1403637203138319104
1403637203188318976
1403637203238319104
1403637203288318976
1403637203338319104
1403637203388318976
1403637203438319104
1403637203488318976
1403637203538319104
1403637203588318976
1403637203638319104
1403637203688318976
1403637203738319104
1403637203788318976
1403637203838319104
1403637203888318976
1403637203938319104
1403637203988318976
1403637204038319104
1403637204088318976
1403637204138319104
1403637204188318976
1403637204238319104
1403637204288318976
1403637204338319104
1403637204388318976
1403637204438319104
1403637204488318976
1403637204538319104
1403637204588318976
1403637204638319104
1403637204688318976
1403637204738319104
1403637204788318976
1403637204838319104
1403637204888318976
1403637204938319104
1403637204988318976
1403637205038319104
1403637205088318976
1403637205138319104
1403637205188318976
1403637205238319104
1403637205288318976
1403637205338319104
1403637205388318976
1403637205438319104
1403637205488318976
1403637205538319104
1403637205588318976
1403637205638319104
1403637205688318976
1403637205738319104
1403637205788318976
1403637205838319104
1403637205888318976
1403637205938319104
1403637205988318976
1403637206038319104
1403637206088318976
1403637206138319104
1403637206188318976
1403637206238319104
1403637206288318976
1403637206338319104
1403637206388318976
1403637206438319104
1403637206488318976
1403637206538319104
1403637206588318976
1403637206638319104
1403637206688318976
1403637206738319104
1403637206788318976
1403637206838319104
1403637206888318976
1403637206938319104
1403637206988318976
1403637207038319104
1403637207088318976
1403637207138319104
1403637207188318976
1403637207238319104
1403637207288318976
1403637207338319104
1403637207388318976
1403637207438319104
1403637207488318976
1403637207538319104
1403637207588318976
1403637207638319104
1403637207688318976
1403637207738319104
1403637207788318976
1403637207838319104
1403637207888318976
1403637207938319104
1403637207988318976
1403637208038319104
1403637208088318976
1403637208138319104
1403637208188318976
1403637208238319104
1403637208288318976
1403637208338319104
1403637208388318976
1403637208438319104
1403637208488318976
1403637208538319104
1403637208588318976
1403637208638319104
1403637208688318976
1403637208738319104
1403637208788318976
1403637208838319104
1403637208888318976
1403637208938319104
1403637208988318976
1403637209038319104
1403637209088318976
1403637209138319104
1403637209188318976
1403637209238319104
1403637209288318976
1403637209338319104
1403637209388318976
1403637209438319104
1403637209488318976
1403637209538319104
1403637209588318976
1403637209638319104
1403637209688318976
1403637209738319104
1403637209788318976
1403637209838319104
1403637209888318976
1403637209938319104
1403637209988318976
1403637210038319104
1403637210088318976
1403637210138319104
1403637210188318976
1403637210238319104
1403637210288318976
1403637210338319104
1403637210388318976
1403637210438319104
1403637210488318976
1403637210538319104
1403637210588318976
1403637210638319104
1403637210688318976
1403637210738319104
1403637210788318976
1403637210838319104
1403637210888318976
1403637210938319104
1403637210988318976
1403637211038319104
1403637211088318976
1403637211138319104
1403637211188318976
1403637211238319104
1403637211288318976
1403637211338319104
1403637211388318976
1403637211438319104
1403637211488318976
1403637211538319104
1403637211588318976
1403637211638319104
1403637211688318976
1403637211738319104
1403637211788318976
1403637211838319104
1403637211888318976
1403637211938319104
1403637211988318976
1403637212038319104
1403637212088318976
1403637212138319104
1403637212188318976
1403637212238319104
1403637212288318976
1403637212338319104
1403637212388318976
1403637212438319104
1403637212488318976
1403637212538319104
1403637212588318976
1403637212638319104
1403637212688318976
1403637212738319104
1403637212788318976
1403637212838319104
1403637212888318976
1403637212938319104
1403637212988318976
1403637213038319104
1403637213088318976
1403637213138319104
1403637213188318976
1403637213238319104
1403637213288318976
1403637213338319104
1403637213388318976
1403637213438319104
1403637213488318976
1403637213538319104
1403637213588318976
1403637213638319104
1403637213688318976
1403637213738319104
1403637213788318976
1403637213838319104
1403637213888318976
1403637213938319104
1403637213988318976
1403637214038319104
1403637214088318976
1403637214138319104
1403637214188318976
1403637214238319104
1403637214288318976
1403637214338319104
1403637214388318976
1403637214438319104
1403637214488318976
1403637214538319104
1403637214588318976
1403637214638319104
1403637214688318976
1403637214738319104
1403637214788318976
1403637214838319104
1403637214888318976
1403637214938319104
1403637214988318976
1403637215038319104
1403637215088318976
1403637215138319104
1403637215188318976
1403637215238319104
1403637215288318976
1403637215338319104
1403637215388318976
1403637215438319104
1403637215488318976
1403637215538319104
1403637215588318976
1403637215638319104
1403637215688318976
1403637215738319104
1403637215788318976
1403637215838319104
1403637215888318976
1403637215938319104
1403637215988318976
1403637216038319104
1403637216088318976
1403637216138319104
1403637216188318976
1403637216238319104
1403637216288318976
1403637216338319104
1403637216388318976
1403637216438319104
1403637216488318976
1403637216538319104
1403637216588318976
1403637216638319104
1403637216688318976
1403637216738319104
1403637216788318976
1403637216838319104
1403637216888318976
1403637216938319104
1403637216988318976
1403637217038319104
1403637217088318976
1403637217138319104
1403637217188318976
1403637217238319104
1403637217288318976
1403637217338319104
1403637217388318976
1403637217438319104
1403637217488318976
1403637217538319104
1403637217588318976
1403637217638319104
1403637217688318976
1403637217738319104
1403637217788318976
1403637217838319104
1403637217888318976
1403637217938319104
1403637217988318976
1403637218038319104
1403637218088318976
1403637218138319104
1403637218188318976
1403637218238319104
1403637218288318976
1403637218338319104
1403637218388318976
1403637218438319104
1403637218488318976
1403637218538319104
1403637218588318976
1403637218638319104
1403637218688318976
1403637218738319104
1403637218788318976
1403637218838319104
1403637218888318976
1403637218938319104
1403637218988318976
1403637219038319104
1403637219088318976
1403637219138319104
1403637219188318976
1403637219238319104
1403637219288318976
1403637219338319104
1403637219388318976
1403637219438319104
1403637219488318976
1403637219538319104
1403637219588318976
1403637219638319104
1403637219688318976
1403637219738319104
1403637219788318976
1403637219838319104
1403637219888318976
1403637219938319104
1403637219988318976
1403637220038319104
1403637220088318976
1403637220138319104
1403637220188318976
1403637220238319104
1403637220288318976
1403637220338319104
1403637220388318976
1403637220438319104
1403637220488318976
1403637220538319104
1403637220588318976
1403637220638319104
1403637220688318976
1403637220738319104
1403637220788318976
1403637220838319104
1403637220888318976
1403637220938319104
1403637220988318976
1403637221038319104
1403637221088318976
1403637221138319104
1403637221188318976
1403637221238319104
1403637221288318976
1403637221338319104
1403637221388318976
1403637221438319104
1403637221488318976
1403637221538319104
1403637221588318976
1403637221638319104
1403637221688318976
1403637221738319104
1403637221788318976
1403637221838319104
1403637221888318976
1403637221938319104
1403637221988318976
1403637222038319104
1403637222088318976
1403637222138319104
1403637222188318976
1403637222238319104
1403637222288318976
1403637222338319104
1403637222388318976
1403637222438319104
1403637222488318976
1403637222538319104
1403637222588318976
1403637222638319104
1403637222688318976
1403637222738319104
1403637222788318976
1403637222838319104
1403637222888318976
1403637222938319104
1403637222988318976
1403637223038319104
1403637223088318976
1403637223138319104
1403637223188318976
1403637223238319104
1403637223288318976
1403637223338319104
1403637223388318976
1403637223438319104
1403637223488318976
1403637223538319104
1403637223588318976
1403637223638319104
1403637223688318976
1403637223738319104
1403637223788318976
1403637223838319104
1403637223888318976
1403637223938319104
1403637223988318976
1403637224038319104
1403637224088318976
1403637224138319104
1403637224188318976
1403637224238319104
1403637224288318976
1403637224338319104
1403637224388318976
1403637224438319104
1403637224488318976
1403637224538319104
1403637224588318976
1403637224638319104
1403637224688318976
1403637224738319104
1403637224788318976
1403637224838319104
1403637224888318976
1403637224938319104
1403637224988318976
1403637225038319104
1403637225088318976
1403637225138319104
1403637225188318976
1403637225238319104
1403637225288318976
1403637225338319104
1403637225388318976
1403637225438319104
1403637225488318976
1403637225538319104
1403637225588318976
1403637225638319104
1403637225688318976
1403637225738319104
1403637225788318976
1403637225838319104
1403637225888318976
1403637225938319104
1403637225988318976
1403637226038319104
1403637226088318976
1403637226138319104
1403637226188318976
1403637226238319104
1403637226288318976
1403637226338319104
1403637226388318976
1403637226438319104
1403637226488318976
1403637226538319104
1403637226588318976
1403637226638319104
1403637226688318976
1403637226738319104
1403637226788318976
1403637226838319104
1403637226888318976
1403637226938319104
1403637226988318976
1403637227038319104
1403637227088318976
1403637227138319104
1403637227188318976
1403637227238319104
1403637227288318976
1403637227338319104
1403637227388318976
1403637227438319104
1403637227488318976
1403637227538319104
1403637227588318976
1403637227638319104
1403637227688318976
1403637227738319104
1403637227788318976
1403637227838319104
1403637227888318976
1403637227938319104
1403637227988318976
1403637228038319104
1403637228088318976
1403637228138319104
1403637228188318976
1403637228238319104
1403637228288318976
1403637228338319104
1403637228388318976
1403637228438319104
1403637228488318976
1403637228538319104
1403637228588318976
1403637228638319104
1403637228688318976
1403637228738319104
1403637228788318976
1403637228838319104
1403637228888318976
1403637228938319104
1403637228988318976
1403637229038319104
1403637229088318976
1403637229138319104
1403637229188318976
1403637229238319104
1403637229288318976
1403637229338319104
1403637229388318976
1403637229438319104
1403637229488318976
1403637229538319104
1403637229588318976
1403637229638319104
1403637229688318976
1403637229738319104
1403637229788318976
1403637229838319104
1403637229888318976
1403637229938319104
1403637229988318976
1403637230038319104
1403637230088318976
1403637230138319104
1403637230188318976
1403637230238319104
1403637230288318976
1403637230338319104
1403637230388318976
1403637230438319104
1403637230488318976
1403637230538319104
1403637230588318976
1403637230638319104
1403637230688318976
1403637230738319104
1403637230788318976
1403637230838319104
1403637230888318976
1403637230938319104
1403637230988318976
1403637231038319104
1403637231088318976
1403637231138319104
1403637231188318976
1403637231238319104
1403637231288318976
1403637231338319104
1403637231388318976
1403637231438319104
1403637231488318976
1403637231538319104
1403637231588318976
1403637231638319104
1403637231688318976
1403637231738319104
1403637231788318976
1403637231838319104
1403637231888318976
1403637231938319104
1403637231988318976
1403637232038319104
1403637232088318976
1403637232138319104
1403637232188318976
1403637232238319104
1403637232288318976
1403637232338319104
1403637232388318976
1403637232438319104
1403637232488318976
1403637232538319104
1403637232588318976
1403637232638319104
1403637232688318976
1403637232738319104
1403637232788318976
1403637232838319104
1403637232888318976
1403637232938319104
1403637232988318976
1403637233038319104
1403637233088318976
1403637233138319104
1403637233188318976
1403637233238319104
1403637233288318976
1403637233338319104
1403637233388318976
1403637233438319104
1403637233488318976
1403637233538319104
1403637233588318976
1403637233638319104
1403637233688318976
1403637233738319104
1403637233788318976
1403637233838319104
1403637233888318976
1403637233938319104
1403637233988318976
1403637234038319104
1403637234088318976
1403637234138319104
1403637234188318976
1403637234238319104
1403637234288318976
1403637234338319104
1403637234388318976
1403637234438319104
1403637234488318976
1403637234538319104
1403637234588318976
1403637234638319104
1403637234688318976
1403637234738319104
1403637234788318976
1403637234838319104
1403637234888318976
1403637234938319104
1403637234988318976
1403637235038319104
1403637235088318976
1403637235138319104
1403637235188318976
1403637235238319104
1403637235288318976
1403637235338319104
1403637235388318976
1403637235438319104
1403637235488318976
1403637235538319104
1403637235588318976
1403637235638319104
1403637235688318976
1403637235738319104
1403637235788318976
1403637235838319104
1403637235888318976
1403637235938319104
1403637235988318976
1403637236038319104
1403637236088318976
1403637236138319104
1403637236188318976
1403637236238319104
1403637236288318976
1403637236338319104
1403637236388318976
1403637236438319104
1403637236488318976
1403637236538319104
1403637236588318976
1403637236638319104
1403637236688318976
1403637236738319104
1403637236788318976
1403637236838319104
1403637236888318976
1403637236938319104
1403637236988318976
1403637237038319104
1403637237088318976
1403637237138319104
1403637237188318976
1403637237238319104
1403637237288318976
1403637237338319104
1403637237388318976
1403637237438319104
1403637237488318976
1403637237538319104
1403637237588318976
1403637237638319104
1403637237688318976
1403637237738319104
1403637237788318976
1403637237838319104
1403637237888318976
1403637237938319104
1403637237988318976
1403637238038319104
1403637238088318976
1403637238138319104
1403637238188318976
1403637238238319104
1403637238288318976
1403637238338319104
1403637238388318976
1403637238438319104
1403637238488318976
1403637238538319104
1403637238588318976
1403637238638319104
1403637238688318976
1403637238738319104
1403637238788318976
1403637238838319104
1403637238888318976
1403637238938319104
1403637238988318976
1403637239038319104
1403637239088318976
1403637239138319104
1403637239188318976
1403637239238319104
1403637239288318976
1403637239338319104
1403637239388318976
1403637239438319104
1403637239488318976
1403637239538319104
1403637239588318976
1403637239638319104
1403637239688318976
1403637239738319104
1403637239788318976
1403637239838319104
1403637239888318976
1403637239938319104
1403637239988318976
1403637240038319104
1403637240088318976
1403637240138319104
1403637240188318976
1403637240238319104
1403637240288318976
1403637240338319104
1403637240388318976
1403637240438319104
1403637240488318976
1403637240538319104
1403637240588318976
1403637240638319104
1403637240688318976
1403637240738319104
1403637240788318976
1403637240838319104
1403637240888318976
1403637240938319104
1403637240988318976
1403637241038319104
1403637241088318976
1403637241138319104
1403637241188318976
1403637241238319104
1403637241288318976
1403637241338319104
1403637241388318976
1403637241438319104
1403637241488318976
1403637241538319104
1403637241588318976
1403637241638319104
1403637241688318976
1403637241738319104
1403637241788318976
1403637241838319104
1403637241888318976
1403637241938319104
1403637241988318976
1403637242038319104
1403637242088318976
1403637242138319104
1403637242188318976
1403637242238319104
1403637242288318976
1403637242338319104
1403637242388318976
1403637242438319104
1403637242488318976
1403637242538319104
1403637242588318976
1403637242638319104
1403637242688318976
1403637242738319104
1403637242788318976
1403637242838319104
1403637242888318976
1403637242938319104
1403637242988318976
1403637243038319104
1403637243088318976
1403637243138319104
1403637243188318976
1403637243238319104
1403637243288318976
1403637243338319104
1403637243388318976
1403637243438319104
1403637243488318976
1403637243538319104
1403637243588318976
1403637243638319104
1403637243688318976
1403637243738319104
1403637243788318976
1403637243838319104
1403637243888318976
1403637243938319104
1403637243988318976
1403637244038319104
1403637244088318976
1403637244138319104
1403637244188318976
1403637244238319104
1403637244288318976
1403637244338319104
1403637244388318976
1403637244438319104
1403637244488318976
1403637244538319104
1403637244588318976
1403637244638319104
1403637244688318976
1403637244738319104
1403637244788318976
1403637244838319104
1403637244888318976
1403637244938319104
1403637244988318976
1403637245038319104
1403637245088318976
1403637245138319104
1403637245188318976
1403637245238319104
1403637245288318976
1403637245338319104
1403637245388318976
1403637245438319104
1403637245488318976
1403637245538319104
1403637245588318976
1403637245638319104
1403637245688318976
1403637245738319104
1403637245788318976
1403637245838319104
1403637245888318976
1403637245938319104
1403637245988318976
1403637246038319104
1403637246088318976
1403637246138319104
1403637246188318976
1403637246238319104
1403637246288318976
1403637246338319104
1403637246388318976
1403637246438319104
1403637246488318976
1403637246538319104
1403637246588318976
1403637246638319104
1403637246688318976
1403637246738319104
1403637246788318976
1403637246838319104
1403637246888318976
1403637246938319104
1403637246988318976
1403637247038319104
1403637247088318976
1403637247138319104
1403637247188318976
1403637247238319104
1403637247288318976
1403637247338319104
1403637247388318976
1403637247438319104
1403637247488318976
1403637247538319104
1403637247588318976
1403637247638319104
1403637247688318976
1403637247738319104
1403637247788318976
1403637247838319104
1403637247888318976
1403637247938319104
1403637247988318976
1403637248038319104
1403637248088318976
1403637248138319104
1403637248188318976
1403637248238319104
1403637248288318976
1403637248338319104
1403637248388318976
1403637248438319104
1403637248488318976
1403637248538319104
1403637248588318976
1403637248638319104
1403637248688318976
1403637248738319104
1403637248788318976
1403637248838319104
1403637248888318976
1403637248938319104
1403637248988318976
1403637249038319104
1403637249088318976
1403637249138319104
1403637249188318976
1403637249238319104
1403637249288318976
1403637249338319104
1403637249388318976
1403637249438319104
1403637249488318976
1403637249538319104
1403637249588318976
1403637249638319104
1403637249688318976
1403637249738319104
1403637249788318976
1403637249838319104
1403637249888318976
1403637249938319104
1403637249988318976
1403637250038319104
1403637250088318976
1403637250138319104
1403637250188318976
1403637250238319104
1403637250288318976
1403637250338319104
1403637250388318976
1403637250438319104
1403637250488318976
1403637250538319104
1403637250588318976
1403637250638319104
1403637250688318976
1403637250738319104
1403637250788318976
1403637250838319104
1403637250888318976
1403637250938319104
1403637250988318976
1403637251038319104
1403637251088318976
1403637251138319104
1403637251188318976
1403637251238319104
1403637251288318976
1403637251338319104
1403637251388318976
1403637251438319104
1403637251488318976
1403637251538319104
1403637251588318976
1403637251638319104
1403637251688318976
1403637251738319104
1403637251788318976
1403637251838319104
1403637251888318976
1403637251938319104
1403637251988318976
1403637252038319104
1403637252088318976
1403637252138319104
1403637252188318976
1403637252238319104
1403637252288318976
1403637252338319104
1403637252388318976
1403637252438319104
1403637252488318976
1403637252538319104
1403637252588318976
1403637252638319104
1403637252688318976
1403637252738319104
1403637252788318976
1403637252838319104
1403637252888318976
1403637252938319104
1403637252988318976
1403637253038319104
1403637253088318976
1403637253138319104
1403637253188318976
1403637253238319104
1403637253288318976
1403637253338319104
1403637253388318976
1403637253438319104
1403637253488318976
1403637253538319104
1403637253588318976
1403637253638319104
1403637253688318976
1403637253738319104
1403637253788318976
1403637253838319104
1403637253888318976
1403637253938319104
1403637253988318976
1403637254038319104
1403637254088318976
1403637254138319104
1403637254188318976
1403637254238319104
1403637254288318976
1403637254338319104
1403637254388318976
1403637254438319104
1403637254488318976
1403637254538319104
1403637254588318976
1403637254638319104
1403637254688318976
1403637254738319104
1403637254788318976
1403637254838319104
1403637254888318976
1403637254938319104
1403637254988318976
1403637255038319104
1403637255088318976
1403637255138319104
1403637255188318976
1403637255238319104
1403637255288318976
1403637255338319104
1403637255388318976
1403637255438319104
1403637255488318976
1403637255538319104
1403637255588318976
1403637255638319104
1403637255688318976
1403637255738319104
1403637255788318976
1403637255838319104
1403637255888318976
1403637255938319104
1403637255988318976
1403637256038319104
1403637256088318976
1403637256138319104
1403637256188318976
1403637256238319104
1403637256288318976
1403637256338319104
1403637256388318976
1403637256438319104
1403637256488318976
1403637256538319104
1403637256588318976
1403637256638319104
1403637256688318976
1403637256738319104
1403637256788318976
1403637256838319104
1403637256888318976
1403637256938319104
1403637256988318976
1403637257038319104
1403637257088318976
1403637257138319104
1403637257188318976
1403637257238319104
1403637257288318976
1403637257338319104
1403637257388318976
1403637257438319104
1403637257488318976
1403637257538319104
1403637257588318976
1403637257638319104
1403637257688318976
1403637257738319104
1403637257788318976
1403637257838319104
1403637257888318976
1403637257938319104
1403637257988318976
1403637258038319104
1403637258088318976
1403637258138319104
1403637258188318976
1403637258238319104
1403637258288318976
1403637258338319104
1403637258388318976
1403637258438319104
1403637258488318976
1403637258538319104
1403637258588318976
1403637258638319104
1403637258688318976
1403637258738319104
1403637258788318976
1403637258838319104
1403637258888318976
1403637258938319104
1403637258988318976
1403637259038319104
1403637259088318976
1403637259138319104
1403637259188318976
1403637259238319104
1403637259288318976
1403637259338319104
1403637259388318976
1403637259438319104
1403637259488318976
1403637259538319104
1403637259588318976
1403637259638319104
1403637259688318976
1403637259738319104
1403637259788318976
1403637259838319104
1403637259888318976
1403637259938319104
1403637259988318976
1403637260038319104
1403637260088318976
1403637260138319104
1403637260188318976
1403637260238319104
1403637260288318976
1403637260338319104
1403637260388318976
1403637260438319104
1403637260488318976
1403637260538319104
1403637260588318976
1403637260638319104
1403637260688318976
1403637260738319104
1403637260788318976
1403637260838319104
1403637260888318976
1403637260938319104
1403637260988318976
1403637261038319104
1403637261088318976
1403637261138319104
1403637261188318976
1403637261238319104
1403637261288318976
1403637261338319104
1403637261388318976
1403637261438319104
1403637261488318976
1403637261538319104
1403637261588318976
1403637261638319104
1403637261688318976
1403637261738319104
1403637261788318976
1403637261838319104
1403637261888318976
1403637261938319104
1403637261988318976
1403637262038319104
1403637262088318976
1403637262138319104
1403637262188318976
1403637262238319104
1403637262288318976
1403637262338319104
1403637262388318976
1403637262438319104
1403637262488318976
1403637262538319104
1403637262588318976
1403637262638319104
1403637262688318976
1403637262738319104
1403637262788318976
1403637262838319104
1403637262888318976
1403637262938319104
1403637262988318976
1403637263038319104
1403637263088318976
1403637263138319104
1403637263188318976
1403637263238319104
1403637263288318976
1403637263338319104
1403637263388318976
1403637263438319104
1403637263488318976
1403637263538319104
1403637263588318976
1403637263638319104
1403637263688318976
1403637263738319104
1403637263788318976
1403637263838319104
1403637263888318976
1403637263938319104
1403637263988318976
1403637264038319104
1403637264088318976
1403637264138319104
1403637264188318976
1403637264238319104
1403637264288318976
1403637264338319104
1403637264388318976
1403637264438319104
1403637264488318976
1403637264538319104
1403637264588318976
1403637264638319104
1403637264688318976
1403637264738319104
1403637264788318976
1403637264838319104
1403637264888318976
1403637264938319104
1403637264988318976
1403637265038319104
1403637265088318976
1403637265138319104
1403637265188318976
1403637265238319104
1403637265288318976
1403637265338319104
1403637265388318976
1403637265438319104
1403637265488318976
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/MH04.txt
================================================
1403638127295097088
1403638127345096960
1403638127395097088
1403638127445096960
1403638127495097088
1403638127545096960
1403638127595097088
1403638127645096960
1403638127695097088
1403638127745096960
1403638127795097088
1403638127845096960
1403638127895097088
1403638127945096960
1403638127995097088
1403638128045096960
1403638128095097088
1403638128145096960
1403638128195097088
1403638128245096960
1403638128295097088
1403638128345096960
1403638128395097088
1403638128445096960
1403638128495097088
1403638128545096960
1403638128595097088
1403638128645096960
1403638128695097088
1403638128745096960
1403638128795097088
1403638128845096960
1403638128895097088
1403638128945096960
1403638128995097088
1403638129045096960
1403638129095097088
1403638129145096960
1403638129195097088
1403638129245096960
1403638129295097088
1403638129345096960
1403638129395097088
1403638129445096960
1403638129495097088
1403638129545096960
1403638129595097088
1403638129645096960
1403638129695097088
1403638129745096960
1403638129795097088
1403638129845096960
1403638129895097088
1403638129945096960
1403638129995097088
1403638130045096960
1403638130095097088
1403638130145096960
1403638130195097088
1403638130245096960
1403638130295097088
1403638130345096960
1403638130395097088
1403638130445096960
1403638130495097088
1403638130545096960
1403638130595097088
1403638130645096960
1403638130695097088
1403638130745096960
1403638130795097088
1403638130845096960
1403638130895097088
1403638130945096960
1403638130995097088
1403638131045096960
1403638131095097088
1403638131145096960
1403638131195097088
1403638131245096960
1403638131295097088
1403638131345096960
1403638131395097088
1403638131445096960
1403638131495097088
1403638131545096960
1403638131595097088
1403638131645096960
1403638131695097088
1403638131745096960
1403638131795097088
1403638131845096960
1403638131895097088
1403638131945096960
1403638131995097088
1403638132045096960
1403638132095097088
1403638132145096960
1403638132195097088
1403638132245096960
1403638132295097088
1403638132345096960
1403638132395097088
1403638132445096960
1403638132495097088
1403638132545096960
1403638132595097088
1403638132645096960
1403638132695097088
1403638132745096960
1403638132795097088
1403638132845096960
1403638132895097088
1403638132945096960
1403638132995097088
1403638133045096960
1403638133095097088
1403638133145096960
1403638133195097088
1403638133245096960
1403638133295097088
1403638133345096960
1403638133395097088
1403638133445096960
1403638133495097088
1403638133545096960
1403638133595097088
1403638133645096960
1403638133695097088
1403638133745096960
1403638133795097088
1403638133845096960
1403638133895097088
1403638133945096960
1403638133995097088
1403638134045096960
1403638134095097088
1403638134145096960
1403638134195097088
1403638134245096960
1403638134295097088
1403638134345096960
1403638134395097088
1403638134445096960
1403638134495097088
1403638134545096960
1403638134595097088
1403638134645096960
1403638134695097088
1403638134745096960
1403638134795097088
1403638134845096960
1403638134895097088
1403638134945096960
1403638134995097088
1403638135045096960
1403638135095097088
1403638135145096960
1403638135195097088
1403638135245096960
1403638135295097088
1403638135345096960
1403638135395097088
1403638135445096960
1403638135495097088
1403638135545096960
1403638135595097088
1403638135645096960
1403638135695097088
1403638135745096960
1403638135795097088
1403638135845096960
1403638135895097088
1403638135945096960
1403638135995097088
1403638136045096960
1403638136095097088
1403638136145096960
1403638136195097088
1403638136245096960
1403638136295097088
1403638136345096960
1403638136395097088
1403638136445096960
1403638136495097088
1403638136545096960
1403638136595097088
1403638136645096960
1403638136695097088
1403638136745096960
1403638136795097088
1403638136845096960
1403638136895097088
1403638136945096960
1403638136995097088
1403638137045096960
1403638137095097088
1403638137145096960
1403638137195097088
1403638137245096960
1403638137295097088
1403638137345096960
1403638137395097088
1403638137445096960
1403638137495097088
1403638137545096960
1403638137595097088
1403638137645096960
1403638137695097088
1403638137745096960
1403638137795097088
1403638137845096960
1403638137895097088
1403638137945096960
1403638137995097088
1403638138045096960
1403638138095097088
1403638138145096960
1403638138195097088
1403638138245096960
1403638138295097088
1403638138345096960
1403638138395097088
1403638138445096960
1403638138495097088
1403638138545096960
1403638138595097088
1403638138645096960
1403638138695097088
1403638138745096960
1403638138795097088
1403638138845096960
1403638138895097088
1403638138945096960
1403638138995097088
1403638139045096960
1403638139095097088
1403638139145096960
1403638139195097088
1403638139245096960
1403638139295097088
1403638139345096960
1403638139395097088
1403638139445096960
1403638139495097088
1403638139545096960
1403638139595097088
1403638139645096960
1403638139695097088
1403638139745096960
1403638139795097088
1403638139845096960
1403638139895097088
1403638139945096960
1403638139995097088
1403638140045096960
1403638140095097088
1403638140145096960
1403638140195097088
1403638140245096960
1403638140295097088
1403638140345096960
1403638140395097088
1403638140445096960
1403638140495097088
1403638140545096960
1403638140595097088
1403638140645096960
1403638140695097088
1403638140745096960
1403638140795097088
1403638140845096960
1403638140895097088
1403638140945096960
1403638140995097088
1403638141045096960
1403638141095097088
1403638141145096960
1403638141195097088
1403638141245096960
1403638141295097088
1403638141345096960
1403638141395097088
1403638141445096960
1403638141495097088
1403638141545096960
1403638141595097088
1403638141645096960
1403638141695097088
1403638141745096960
1403638141795097088
1403638141845096960
1403638141895097088
1403638141945096960
1403638141995097088
1403638142045096960
1403638142095097088
1403638142145096960
1403638142195097088
1403638142245096960
1403638142295097088
1403638142345096960
1403638142395097088
1403638142445096960
1403638142495097088
1403638142545096960
1403638142595097088
1403638142645096960
1403638142695097088
1403638142745096960
1403638142795097088
1403638142845096960
1403638142895097088
1403638142945096960
1403638142995097088
1403638143045096960
1403638143095097088
1403638143145096960
1403638143195097088
1403638143245096960
1403638143295097088
1403638143345096960
1403638143395097088
1403638143445096960
1403638143495097088
1403638143545096960
1403638143595097088
1403638143645096960
1403638143695097088
1403638143745096960
1403638143795097088
1403638143845096960
1403638143895097088
1403638143945096960
1403638143995097088
1403638144045096960
1403638144095097088
1403638144145096960
1403638144195097088
1403638144245096960
1403638144295097088
1403638144345096960
1403638144395097088
1403638144445096960
1403638144495097088
1403638144545096960
1403638144595097088
1403638144645096960
1403638144695097088
1403638144745096960
1403638144795097088
1403638144845096960
1403638144895097088
1403638144945096960
1403638144995097088
1403638145045096960
1403638145095097088
1403638145145096960
1403638145195097088
1403638145245096960
1403638145295097088
1403638145345096960
1403638145395097088
1403638145445096960
1403638145495097088
1403638145545096960
1403638145595097088
1403638145645096960
1403638145695097088
1403638145745096960
1403638145795097088
1403638145845096960
1403638145895097088
1403638145945096960
1403638145995097088
1403638146045096960
1403638146095097088
1403638146145096960
1403638146195097088
1403638146245096960
1403638146295097088
1403638146345096960
1403638146395097088
1403638146445096960
1403638146495097088
1403638146545096960
1403638146595097088
1403638146645096960
1403638146695097088
1403638146745096960
1403638146795097088
1403638146845096960
1403638146895097088
1403638146945096960
1403638146995097088
1403638147045096960
1403638147095097088
1403638147145096960
1403638147195097088
1403638147245096960
1403638147295097088
1403638147345096960
1403638147395097088
1403638147445096960
1403638147495097088
1403638147545096960
1403638147595097088
1403638147645096960
1403638147695097088
1403638147745096960
1403638147795097088
1403638147845096960
1403638147895097088
1403638147945096960
1403638147995097088
1403638148045096960
1403638148095097088
1403638148145096960
1403638148195097088
1403638148245096960
1403638148295097088
1403638148345096960
1403638148395097088
1403638148445096960
1403638148495097088
1403638148545096960
1403638148595097088
1403638148645096960
1403638148695097088
1403638148745096960
1403638148795097088
1403638148845096960
1403638148895097088
1403638148945096960
1403638148995097088
1403638149045096960
1403638149095097088
1403638149145096960
1403638149195097088
1403638149245096960
1403638149295097088
1403638149345096960
1403638149395097088
1403638149445096960
1403638149495097088
1403638149545096960
1403638149595097088
1403638149645096960
1403638149695097088
1403638149745096960
1403638149795097088
1403638149845096960
1403638149895097088
1403638149945096960
1403638149995097088
1403638150045096960
1403638150095097088
1403638150145096960
1403638150195097088
1403638150245096960
1403638150295097088
1403638150345096960
1403638150395097088
1403638150445096960
1403638150495097088
1403638150545096960
1403638150595097088
1403638150645096960
1403638150695097088
1403638150745096960
1403638150795097088
1403638150845096960
1403638150895097088
1403638150945096960
1403638150995097088
1403638151045096960
1403638151095097088
1403638151145096960
1403638151195097088
1403638151245096960
1403638151295097088
1403638151345096960
1403638151395097088
1403638151445096960
1403638151495097088
1403638151545096960
1403638151595097088
1403638151645096960
1403638151695097088
1403638151745096960
1403638151795097088
1403638151845096960
1403638151895097088
1403638151945096960
1403638151995097088
1403638152045096960
1403638152095097088
1403638152145096960
1403638152195097088
1403638152245096960
1403638152295097088
1403638152345096960
1403638152395097088
1403638152445096960
1403638152495097088
1403638152545096960
1403638152595097088
1403638152645096960
1403638152695097088
1403638152745096960
1403638152795097088
1403638152845096960
1403638152895097088
1403638152945096960
1403638152995097088
1403638153045096960
1403638153095097088
1403638153145096960
1403638153195097088
1403638153245096960
1403638153295097088
1403638153345096960
1403638153395097088
1403638153445096960
1403638153495097088
1403638153545096960
1403638153595097088
1403638153645096960
1403638153695097088
1403638153745096960
1403638153795097088
1403638153845096960
1403638153895097088
1403638153945096960
1403638153995097088
1403638154045096960
1403638154095097088
1403638154145096960
1403638154195097088
1403638154245096960
1403638154295097088
1403638154345096960
1403638154395097088
1403638154445096960
1403638154495097088
1403638154545096960
1403638154595097088
1403638154645096960
1403638154695097088
1403638154745096960
1403638154795097088
1403638154845096960
1403638154895097088
1403638154945096960
1403638154995097088
1403638155045096960
1403638155095097088
1403638155145096960
1403638155195097088
1403638155245096960
1403638155295097088
1403638155345096960
1403638155395097088
1403638155445096960
1403638155495097088
1403638155545096960
1403638155595097088
1403638155645096960
1403638155695097088
1403638155745096960
1403638155795097088
1403638155845096960
1403638155895097088
1403638155945096960
1403638155995097088
1403638156045096960
1403638156095097088
1403638156145096960
1403638156195097088
1403638156245096960
1403638156295097088
1403638156345096960
1403638156395097088
1403638156445096960
1403638156495097088
1403638156545096960
1403638156595097088
1403638156645096960
1403638156695097088
1403638156745096960
1403638156795097088
1403638156845096960
1403638156895097088
1403638156945096960
1403638156995097088
1403638157045096960
1403638157095097088
1403638157145096960
1403638157195097088
1403638157245096960
1403638157295097088
1403638157345096960
1403638157395097088
1403638157445096960
1403638157495097088
1403638157545096960
1403638157595097088
1403638157645096960
1403638157695097088
1403638157745096960
1403638157795097088
1403638157845096960
1403638157895097088
1403638157945096960
1403638157995097088
1403638158045096960
1403638158095097088
1403638158145096960
1403638158195097088
1403638158245096960
1403638158295097088
1403638158345096960
1403638158395097088
1403638158445096960
1403638158495097088
1403638158545096960
1403638158595097088
1403638158645096960
1403638158695097088
1403638158745096960
1403638158795097088
1403638158845096960
1403638158895097088
1403638158945096960
1403638158995097088
1403638159045096960
1403638159095097088
1403638159145096960
1403638159195097088
1403638159245096960
1403638159295097088
1403638159345096960
1403638159395097088
1403638159445096960
1403638159495097088
1403638159545096960
1403638159595097088
1403638159645096960
1403638159695097088
1403638159745096960
1403638159795097088
1403638159845096960
1403638159895097088
1403638159945096960
1403638159995097088
1403638160045096960
1403638160095097088
1403638160145096960
1403638160195097088
1403638160245096960
1403638160295097088
1403638160345096960
1403638160395097088
1403638160445096960
1403638160495097088
1403638160545096960
1403638160595097088
1403638160645096960
1403638160695097088
1403638160745096960
1403638160795097088
1403638160845096960
1403638160895097088
1403638160945096960
1403638160995097088
1403638161045096960
1403638161095097088
1403638161145096960
1403638161195097088
1403638161245096960
1403638161295097088
1403638161345096960
1403638161395097088
1403638161445096960
1403638161495097088
1403638161545096960
1403638161595097088
1403638161645096960
1403638161695097088
1403638161745096960
1403638161795097088
1403638161845096960
1403638161895097088
1403638161945096960
1403638161995097088
1403638162045096960
1403638162095097088
1403638162145096960
1403638162195097088
1403638162245096960
1403638162295097088
1403638162345096960
1403638162395097088
1403638162445096960
1403638162495097088
1403638162545096960
1403638162595097088
1403638162645096960
1403638162695097088
1403638162745096960
1403638162795097088
1403638162845096960
1403638162895097088
1403638162945096960
1403638162995097088
1403638163045096960
1403638163095097088
1403638163145096960
1403638163195097088
1403638163245096960
1403638163295097088
1403638163345096960
1403638163395097088
1403638163445096960
1403638163495097088
1403638163545096960
1403638163595097088
1403638163645096960
1403638163695097088
1403638163745096960
1403638163795097088
1403638163845096960
1403638163895097088
1403638163945096960
1403638163995097088
1403638164045096960
1403638164095097088
1403638164145096960
1403638164195097088
1403638164245096960
1403638164295097088
1403638164345096960
1403638164395097088
1403638164445096960
1403638164495097088
1403638164545096960
1403638164595097088
1403638164645096960
1403638164695097088
1403638164745096960
1403638164795097088
1403638164845096960
1403638164895097088
1403638164945096960
1403638164995097088
1403638165045096960
1403638165095097088
1403638165145096960
1403638165195097088
1403638165245096960
1403638165295097088
1403638165345096960
1403638165395097088
1403638165445096960
1403638165495097088
1403638165545096960
1403638165595097088
1403638165645096960
1403638165695097088
1403638165745096960
1403638165795097088
1403638165845096960
1403638165895097088
1403638165945096960
1403638165995097088
1403638166045096960
1403638166095097088
1403638166145096960
1403638166195097088
1403638166245096960
1403638166295097088
1403638166345096960
1403638166395097088
1403638166445096960
1403638166495097088
1403638166545096960
1403638166595097088
1403638166645096960
1403638166695097088
1403638166745096960
1403638166795097088
1403638166845096960
1403638166895097088
1403638166945096960
1403638166995097088
1403638167045096960
1403638167095097088
1403638167145096960
1403638167195097088
1403638167245096960
1403638167295097088
1403638167345096960
1403638167395097088
1403638167445096960
1403638167495097088
1403638167545096960
1403638167595097088
1403638167645096960
1403638167695097088
1403638167745096960
1403638167795097088
1403638167845096960
1403638167895097088
1403638167945096960
1403638167995097088
1403638168045096960
1403638168095097088
1403638168145096960
1403638168195097088
1403638168245096960
1403638168295097088
1403638168345096960
1403638168395097088
1403638168445096960
1403638168495097088
1403638168545096960
1403638168595097088
1403638168645096960
1403638168695097088
1403638168745096960
1403638168795097088
1403638168845096960
1403638168895097088
1403638168945096960
1403638168995097088
1403638169045096960
1403638169095097088
1403638169145096960
1403638169195097088
1403638169245096960
1403638169295097088
1403638169345096960
1403638169395097088
1403638169445096960
1403638169495097088
1403638169545096960
1403638169595097088
1403638169645096960
1403638169695097088
1403638169745096960
1403638169795097088
1403638169845096960
1403638169895097088
1403638169945096960
1403638169995097088
1403638170045096960
1403638170095097088
1403638170145096960
1403638170195097088
1403638170245096960
1403638170295097088
1403638170345096960
1403638170395097088
1403638170445096960
1403638170495097088
1403638170545096960
1403638170595097088
1403638170645096960
1403638170695097088
1403638170745096960
1403638170795097088
1403638170845096960
1403638170895097088
1403638170945096960
1403638170995097088
1403638171045096960
1403638171095097088
1403638171145096960
1403638171195097088
1403638171245096960
1403638171295097088
1403638171345096960
1403638171395097088
1403638171445096960
1403638171495097088
1403638171545096960
1403638171595097088
1403638171645096960
1403638171695097088
1403638171745096960
1403638171795097088
1403638171845096960
1403638171895097088
1403638171945096960
1403638171995097088
1403638172045096960
1403638172095097088
1403638172145096960
1403638172195097088
1403638172245096960
1403638172295097088
1403638172345096960
1403638172395097088
1403638172445096960
1403638172495097088
1403638172545096960
1403638172595097088
1403638172645096960
1403638172695097088
1403638172745096960
1403638172795097088
1403638172845096960
1403638172895097088
1403638172945096960
1403638172995097088
1403638173045096960
1403638173095097088
1403638173145096960
1403638173195097088
1403638173245096960
1403638173295097088
1403638173345096960
1403638173395097088
1403638173445096960
1403638173495097088
1403638173545096960
1403638173595097088
1403638173645096960
1403638173695097088
1403638173745096960
1403638173795097088
1403638173845096960
1403638173895097088
1403638173945096960
1403638173995097088
1403638174045096960
1403638174095097088
1403638174145096960
1403638174195097088
1403638174245096960
1403638174295097088
1403638174345096960
1403638174395097088
1403638174445096960
1403638174495097088
1403638174545096960
1403638174595097088
1403638174645096960
1403638174695097088
1403638174745096960
1403638174795097088
1403638174845096960
1403638174895097088
1403638174945096960
1403638174995097088
1403638175045096960
1403638175095097088
1403638175145096960
1403638175195097088
1403638175245096960
1403638175295097088
1403638175345096960
1403638175395097088
1403638175445096960
1403638175495097088
1403638175545096960
1403638175595097088
1403638175645096960
1403638175695097088
1403638175745096960
1403638175795097088
1403638175845096960
1403638175895097088
1403638175945096960
1403638175995097088
1403638176045096960
1403638176095097088
1403638176145096960
1403638176195097088
1403638176245096960
1403638176295097088
1403638176345096960
1403638176395097088
1403638176445096960
1403638176495097088
1403638176545096960
1403638176595097088
1403638176645096960
1403638176695097088
1403638176745096960
1403638176795097088
1403638176845096960
1403638176895097088
1403638176945096960
1403638176995097088
1403638177045096960
1403638177095097088
1403638177145096960
1403638177195097088
1403638177245096960
1403638177295097088
1403638177345096960
1403638177395097088
1403638177445096960
1403638177495097088
1403638177545096960
1403638177595097088
1403638177645096960
1403638177695097088
1403638177745096960
1403638177795097088
1403638177845096960
1403638177895097088
1403638177945096960
1403638177995097088
1403638178045096960
1403638178095097088
1403638178145096960
1403638178195097088
1403638178245096960
1403638178295097088
1403638178345096960
1403638178395097088
1403638178445096960
1403638178495097088
1403638178545096960
1403638178595097088
1403638178645096960
1403638178695097088
1403638178745096960
1403638178795097088
1403638178845096960
1403638178895097088
1403638178945096960
1403638178995097088
1403638179045096960
1403638179095097088
1403638179145096960
1403638179195097088
1403638179245096960
1403638179295097088
1403638179345096960
1403638179395097088
1403638179445096960
1403638179495097088
1403638179545096960
1403638179595097088
1403638179645096960
1403638179695097088
1403638179745096960
1403638179795097088
1403638179845096960
1403638179895097088
1403638179945096960
1403638179995097088
1403638180045096960
1403638180095097088
1403638180145096960
1403638180195097088
1403638180245096960
1403638180295097088
1403638180345096960
1403638180395097088
1403638180445096960
1403638180495097088
1403638180545096960
1403638180595097088
1403638180645096960
1403638180695097088
1403638180745096960
1403638180795097088
1403638180845096960
1403638180895097088
1403638180945096960
1403638180995097088
1403638181045096960
1403638181095097088
1403638181145096960
1403638181195097088
1403638181245096960
1403638181295097088
1403638181345096960
1403638181395097088
1403638181445096960
1403638181495097088
1403638181545096960
1403638181595097088
1403638181645096960
1403638181695097088
1403638181745096960
1403638181795097088
1403638181845096960
1403638181895097088
1403638181945096960
1403638181995097088
1403638182045096960
1403638182095097088
1403638182145096960
1403638182195097088
1403638182245096960
1403638182295097088
1403638182345096960
1403638182395097088
1403638182445096960
1403638182495097088
1403638182545096960
1403638182595097088
1403638182645096960
1403638182695097088
1403638182745096960
1403638182795097088
1403638182845096960
1403638182895097088
1403638182945096960
1403638182995097088
1403638183045096960
1403638183095097088
1403638183145096960
1403638183195097088
1403638183245096960
1403638183295097088
1403638183345096960
1403638183395097088
1403638183445096960
1403638183495097088
1403638183545096960
1403638183595097088
1403638183645096960
1403638183695097088
1403638183745096960
1403638183795097088
1403638183845096960
1403638183895097088
1403638183945096960
1403638183995097088
1403638184045096960
1403638184095097088
1403638184145096960
1403638184195097088
1403638184245096960
1403638184295097088
1403638184345096960
1403638184395097088
1403638184445096960
1403638184495097088
1403638184545096960
1403638184595097088
1403638184645096960
1403638184695097088
1403638184745096960
1403638184795097088
1403638184845096960
1403638184895097088
1403638184945096960
1403638184995097088
1403638185045096960
1403638185095097088
1403638185145096960
1403638185195097088
1403638185245096960
1403638185295097088
1403638185345096960
1403638185395097088
1403638185445096960
1403638185495097088
1403638185545096960
1403638185595097088
1403638185645096960
1403638185695097088
1403638185745096960
1403638185795097088
1403638185845096960
1403638185895097088
1403638185945096960
1403638185995097088
1403638186045096960
1403638186095097088
1403638186145096960
1403638186195097088
1403638186245096960
1403638186295097088
1403638186345096960
1403638186395097088
1403638186445096960
1403638186495097088
1403638186545096960
1403638186595097088
1403638186645096960
1403638186695097088
1403638186745096960
1403638186795097088
1403638186845096960
1403638186895097088
1403638186945096960
1403638186995097088
1403638187045096960
1403638187095097088
1403638187145096960
1403638187195097088
1403638187245096960
1403638187295097088
1403638187345096960
1403638187395097088
1403638187445096960
1403638187495097088
1403638187545096960
1403638187595097088
1403638187645096960
1403638187695097088
1403638187745096960
1403638187795097088
1403638187845096960
1403638187895097088
1403638187945096960
1403638187995097088
1403638188045096960
1403638188095097088
1403638188145096960
1403638188195097088
1403638188245096960
1403638188295097088
1403638188345096960
1403638188395097088
1403638188445096960
1403638188495097088
1403638188545096960
1403638188595097088
1403638188645096960
1403638188695097088
1403638188745096960
1403638188795097088
1403638188845096960
1403638188895097088
1403638188945096960
1403638188995097088
1403638189045096960
1403638189095097088
1403638189145096960
1403638189195097088
1403638189245096960
1403638189295097088
1403638189345096960
1403638189395097088
1403638189445096960
1403638189495097088
1403638189545096960
1403638189595097088
1403638189645096960
1403638189695097088
1403638189745096960
1403638189795097088
1403638189845096960
1403638189895097088
1403638189945096960
1403638189995097088
1403638190045096960
1403638190095097088
1403638190145096960
1403638190195097088
1403638190245096960
1403638190295097088
1403638190345096960
1403638190395097088
1403638190445096960
1403638190495097088
1403638190545096960
1403638190595097088
1403638190645096960
1403638190695097088
1403638190745096960
1403638190795097088
1403638190845096960
1403638190895097088
1403638190945096960
1403638190995097088
1403638191045096960
1403638191095097088
1403638191145096960
1403638191195097088
1403638191245096960
1403638191295097088
1403638191345096960
1403638191395097088
1403638191445096960
1403638191495097088
1403638191545096960
1403638191595097088
1403638191645096960
1403638191695097088
1403638191745096960
1403638191795097088
1403638191845096960
1403638191895097088
1403638191945096960
1403638191995097088
1403638192045096960
1403638192095097088
1403638192145096960
1403638192195097088
1403638192245096960
1403638192295097088
1403638192345096960
1403638192395097088
1403638192445096960
1403638192495097088
1403638192545096960
1403638192595097088
1403638192645096960
1403638192695097088
1403638192745096960
1403638192795097088
1403638192845096960
1403638192895097088
1403638192945096960
1403638192995097088
1403638193045096960
1403638193095097088
1403638193145096960
1403638193195097088
1403638193245096960
1403638193295097088
1403638193345096960
1403638193395097088
1403638193445096960
1403638193495097088
1403638193545096960
1403638193595097088
1403638193645096960
1403638193695097088
1403638193745096960
1403638193795097088
1403638193845096960
1403638193895097088
1403638193945096960
1403638193995097088
1403638194045096960
1403638194095097088
1403638194145096960
1403638194195097088
1403638194245096960
1403638194295097088
1403638194345096960
1403638194395097088
1403638194445096960
1403638194495097088
1403638194545096960
1403638194595097088
1403638194645096960
1403638194695097088
1403638194745096960
1403638194795097088
1403638194845096960
1403638194895097088
1403638194945096960
1403638194995097088
1403638195045096960
1403638195095097088
1403638195145096960
1403638195195097088
1403638195245096960
1403638195295097088
1403638195345096960
1403638195395097088
1403638195445096960
1403638195495097088
1403638195545096960
1403638195595097088
1403638195645096960
1403638195695097088
1403638195745096960
1403638195795097088
1403638195845096960
1403638195895097088
1403638195945096960
1403638195995097088
1403638196045096960
1403638196095097088
1403638196145096960
1403638196195097088
1403638196245096960
1403638196295097088
1403638196345096960
1403638196395097088
1403638196445096960
1403638196495097088
1403638196545096960
1403638196595097088
1403638196645096960
1403638196695097088
1403638196745096960
1403638196795097088
1403638196845096960
1403638196895097088
1403638196945096960
1403638196995097088
1403638197045096960
1403638197095097088
1403638197145096960
1403638197195097088
1403638197245096960
1403638197295097088
1403638197345096960
1403638197395097088
1403638197445096960
1403638197495097088
1403638197545096960
1403638197595097088
1403638197645096960
1403638197695097088
1403638197745096960
1403638197795097088
1403638197845096960
1403638197895097088
1403638197945096960
1403638197995097088
1403638198045096960
1403638198095097088
1403638198145096960
1403638198195097088
1403638198245096960
1403638198295097088
1403638198345096960
1403638198395097088
1403638198445096960
1403638198495097088
1403638198545096960
1403638198595097088
1403638198645096960
1403638198695097088
1403638198745096960
1403638198795097088
1403638198845096960
1403638198895097088
1403638198945096960
1403638198995097088
1403638199045096960
1403638199095097088
1403638199145096960
1403638199195097088
1403638199245096960
1403638199295097088
1403638199345096960
1403638199395097088
1403638199445096960
1403638199495097088
1403638199545096960
1403638199595097088
1403638199645096960
1403638199695097088
1403638199745096960
1403638199795097088
1403638199845096960
1403638199895097088
1403638199945096960
1403638199995097088
1403638200045096960
1403638200095097088
1403638200145096960
1403638200195097088
1403638200245096960
1403638200295097088
1403638200345096960
1403638200395097088
1403638200445096960
1403638200495097088
1403638200545096960
1403638200595097088
1403638200645096960
1403638200695097088
1403638200745096960
1403638200795097088
1403638200845096960
1403638200895097088
1403638200945096960
1403638200995097088
1403638201045096960
1403638201095097088
1403638201145096960
1403638201195097088
1403638201245096960
1403638201295097088
1403638201345096960
1403638201395097088
1403638201445096960
1403638201495097088
1403638201545096960
1403638201595097088
1403638201645096960
1403638201695097088
1403638201745096960
1403638201795097088
1403638201845096960
1403638201895097088
1403638201945096960
1403638201995097088
1403638202045096960
1403638202095097088
1403638202145096960
1403638202195097088
1403638202245096960
1403638202295097088
1403638202345096960
1403638202395097088
1403638202445096960
1403638202495097088
1403638202545096960
1403638202595097088
1403638202645096960
1403638202695097088
1403638202745096960
1403638202795097088
1403638202845096960
1403638202895097088
1403638202945096960
1403638202995097088
1403638203045096960
1403638203095097088
1403638203145096960
1403638203195097088
1403638203245096960
1403638203295097088
1403638203345096960
1403638203395097088
1403638203445096960
1403638203495097088
1403638203545096960
1403638203595097088
1403638203645096960
1403638203695097088
1403638203745096960
1403638203795097088
1403638203845096960
1403638203895097088
1403638203945096960
1403638203995097088
1403638204045096960
1403638204095097088
1403638204145096960
1403638204195097088
1403638204245096960
1403638204295097088
1403638204345096960
1403638204395097088
1403638204445096960
1403638204495097088
1403638204545096960
1403638204595097088
1403638204645096960
1403638204695097088
1403638204745096960
1403638204795097088
1403638204845096960
1403638204895097088
1403638204945096960
1403638204995097088
1403638205045096960
1403638205095097088
1403638205145096960
1403638205195097088
1403638205245096960
1403638205295097088
1403638205345096960
1403638205395097088
1403638205445096960
1403638205495097088
1403638205545096960
1403638205595097088
1403638205645096960
1403638205695097088
1403638205745096960
1403638205795097088
1403638205845096960
1403638205895097088
1403638205945096960
1403638205995097088
1403638206045096960
1403638206095097088
1403638206145096960
1403638206195097088
1403638206245096960
1403638206295097088
1403638206345096960
1403638206395097088
1403638206445096960
1403638206495097088
1403638206545096960
1403638206595097088
1403638206645096960
1403638206695097088
1403638206745096960
1403638206795097088
1403638206845096960
1403638206895097088
1403638206945096960
1403638206995097088
1403638207045096960
1403638207095097088
1403638207145096960
1403638207195097088
1403638207245096960
1403638207295097088
1403638207345096960
1403638207395097088
1403638207445096960
1403638207495097088
1403638207545096960
1403638207595097088
1403638207645096960
1403638207695097088
1403638207745096960
1403638207795097088
1403638207845096960
1403638207895097088
1403638207945096960
1403638207995097088
1403638208045096960
1403638208095097088
1403638208145096960
1403638208195097088
1403638208245096960
1403638208295097088
1403638208345096960
1403638208395097088
1403638208445096960
1403638208495097088
1403638208545096960
1403638208595097088
1403638208645096960
1403638208695097088
1403638208745096960
1403638208795097088
1403638208845096960
1403638208895097088
1403638208945096960
1403638208995097088
1403638209045096960
1403638209095097088
1403638209145096960
1403638209195097088
1403638209245096960
1403638209295097088
1403638209345096960
1403638209395097088
1403638209445096960
1403638209495097088
1403638209545096960
1403638209595097088
1403638209645096960
1403638209695097088
1403638209745096960
1403638209795097088
1403638209845096960
1403638209895097088
1403638209945096960
1403638209995097088
1403638210045096960
1403638210095097088
1403638210145096960
1403638210195097088
1403638210245096960
1403638210295097088
1403638210345096960
1403638210395097088
1403638210445096960
1403638210495097088
1403638210545096960
1403638210595097088
1403638210645096960
1403638210695097088
1403638210745096960
1403638210795097088
1403638210845096960
1403638210895097088
1403638210945096960
1403638210995097088
1403638211045096960
1403638211095097088
1403638211145096960
1403638211195097088
1403638211245096960
1403638211295097088
1403638211345096960
1403638211395097088
1403638211445096960
1403638211495097088
1403638211545096960
1403638211595097088
1403638211645096960
1403638211695097088
1403638211745096960
1403638211795097088
1403638211845096960
1403638211895097088
1403638211945096960
1403638211995097088
1403638212045096960
1403638212095097088
1403638212145096960
1403638212195097088
1403638212245096960
1403638212295097088
1403638212345096960
1403638212395097088
1403638212445096960
1403638212495097088
1403638212545096960
1403638212595097088
1403638212645096960
1403638212695097088
1403638212745096960
1403638212795097088
1403638212845096960
1403638212895097088
1403638212945096960
1403638212995097088
1403638213045096960
1403638213095097088
1403638213145096960
1403638213195097088
1403638213245096960
1403638213295097088
1403638213345096960
1403638213395097088
1403638213445096960
1403638213495097088
1403638213545096960
1403638213595097088
1403638213645096960
1403638213695097088
1403638213745096960
1403638213795097088
1403638213845096960
1403638213895097088
1403638213945096960
1403638213995097088
1403638214045096960
1403638214095097088
1403638214145096960
1403638214195097088
1403638214245096960
1403638214295097088
1403638214345096960
1403638214395097088
1403638214445096960
1403638214495097088
1403638214545096960
1403638214595097088
1403638214645096960
1403638214695097088
1403638214745096960
1403638214795097088
1403638214845096960
1403638214895097088
1403638214945096960
1403638214995097088
1403638215045096960
1403638215095097088
1403638215145096960
1403638215195097088
1403638215245096960
1403638215295097088
1403638215345096960
1403638215395097088
1403638215445096960
1403638215495097088
1403638215545096960
1403638215595097088
1403638215645096960
1403638215695097088
1403638215745096960
1403638215795097088
1403638215845096960
1403638215895097088
1403638215945096960
1403638215995097088
1403638216045096960
1403638216095097088
1403638216145096960
1403638216195097088
1403638216245096960
1403638216295097088
1403638216345096960
1403638216395097088
1403638216445096960
1403638216495097088
1403638216545096960
1403638216595097088
1403638216645096960
1403638216695097088
1403638216745096960
1403638216795097088
1403638216845096960
1403638216895097088
1403638216945096960
1403638216995097088
1403638217045096960
1403638217095097088
1403638217145096960
1403638217195097088
1403638217245096960
1403638217295097088
1403638217345096960
1403638217395097088
1403638217445096960
1403638217495097088
1403638217545096960
1403638217595097088
1403638217645096960
1403638217695097088
1403638217745096960
1403638217795097088
1403638217845096960
1403638217895097088
1403638217945096960
1403638217995097088
1403638218045096960
1403638218095097088
1403638218145096960
1403638218195097088
1403638218245096960
1403638218295097088
1403638218345096960
1403638218395097088
1403638218445096960
1403638218495097088
1403638218545096960
1403638218595097088
1403638218645096960
1403638218695097088
1403638218745096960
1403638218795097088
1403638218845096960
1403638218895097088
1403638218945096960
1403638218995097088
1403638219045096960
1403638219095097088
1403638219145096960
1403638219195097088
1403638219245096960
1403638219295097088
1403638219345096960
1403638219395097088
1403638219445096960
1403638219495097088
1403638219545096960
1403638219595097088
1403638219645096960
1403638219695097088
1403638219745096960
1403638219795097088
1403638219845096960
1403638219895097088
1403638219945096960
1403638219995097088
1403638220045096960
1403638220095097088
1403638220145096960
1403638220195097088
1403638220245096960
1403638220295097088
1403638220345096960
1403638220395097088
1403638220445096960
1403638220495097088
1403638220545096960
1403638220595097088
1403638220645096960
1403638220695097088
1403638220745096960
1403638220795097088
1403638220845096960
1403638220895097088
1403638220945096960
1403638220995097088
1403638221045096960
1403638221095097088
1403638221145096960
1403638221195097088
1403638221245096960
1403638221295097088
1403638221345096960
1403638221395097088
1403638221445096960
1403638221495097088
1403638221545096960
1403638221595097088
1403638221645096960
1403638221695097088
1403638221745096960
1403638221795097088
1403638221845096960
1403638221895097088
1403638221945096960
1403638221995097088
1403638222045096960
1403638222095097088
1403638222145096960
1403638222195097088
1403638222245096960
1403638222295097088
1403638222345096960
1403638222395097088
1403638222445096960
1403638222495097088
1403638222545096960
1403638222595097088
1403638222645096960
1403638222695097088
1403638222745096960
1403638222795097088
1403638222845096960
1403638222895097088
1403638222945096960
1403638222995097088
1403638223045096960
1403638223095097088
1403638223145096960
1403638223195097088
1403638223245096960
1403638223295097088
1403638223345096960
1403638223395097088
1403638223445096960
1403638223495097088
1403638223545096960
1403638223595097088
1403638223645096960
1403638223695097088
1403638223745096960
1403638223795097088
1403638223845096960
1403638223895097088
1403638223945096960
1403638223995097088
1403638224045096960
1403638224095097088
1403638224145096960
1403638224195097088
1403638224245096960
1403638224295097088
1403638224345096960
1403638224395097088
1403638224445096960
1403638224495097088
1403638224545096960
1403638224595097088
1403638224645096960
1403638224695097088
1403638224745096960
1403638224795097088
1403638224845096960
1403638224895097088
1403638224945096960
1403638224995097088
1403638225045096960
1403638225095097088
1403638225145096960
1403638225195097088
1403638225245096960
1403638225295097088
1403638225345096960
1403638225395097088
1403638225445096960
1403638225495097088
1403638225545096960
1403638225595097088
1403638225645096960
1403638225695097088
1403638225745096960
1403638225795097088
1403638225845096960
1403638225895097088
1403638225945096960
1403638225995097088
1403638226045096960
1403638226095097088
1403638226145096960
1403638226195097088
1403638226245096960
1403638226295097088
1403638226345096960
1403638226395097088
1403638226445096960
1403638226495097088
1403638226545096960
1403638226595097088
1403638226645096960
1403638226695097088
1403638226745096960
1403638226795097088
1403638226845096960
1403638226895097088
1403638226945096960
1403638226995097088
1403638227045096960
1403638227095097088
1403638227145096960
1403638227195097088
1403638227245096960
1403638227295097088
1403638227345096960
1403638227395097088
1403638227445096960
1403638227495097088
1403638227545096960
1403638227595097088
1403638227645096960
1403638227695097088
1403638227745096960
1403638227795097088
1403638227845096960
1403638227895097088
1403638227945096960
1403638227995097088
1403638228045096960
1403638228095097088
1403638228145096960
1403638228195097088
1403638228245096960
1403638228295097088
1403638228345096960
1403638228395097088
1403638228445096960
1403638228495097088
1403638228545096960
1403638228595097088
1403638228645096960
1403638228695097088
1403638228745096960
1403638228795097088
1403638228845096960
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/MH05.txt
================================================
1403638518077829376
1403638518127829504
1403638518177829376
1403638518227829504
1403638518277829376
1403638518327829504
1403638518377829376
1403638518427829504
1403638518477829376
1403638518527829504
1403638518577829376
1403638518627829504
1403638518677829376
1403638518727829504
1403638518777829376
1403638518827829504
1403638518877829376
1403638518927829504
1403638518977829376
1403638519027829504
1403638519077829376
1403638519127829504
1403638519177829376
1403638519227829504
1403638519277829376
1403638519327829504
1403638519377829376
1403638519427829504
1403638519477829376
1403638519527829504
1403638519577829376
1403638519627829504
1403638519677829376
1403638519727829504
1403638519777829376
1403638519827829504
1403638519877829376
1403638519927829504
1403638519977829376
1403638520027829504
1403638520077829376
1403638520127829504
1403638520177829376
1403638520227829504
1403638520277829376
1403638520327829504
1403638520377829376
1403638520427829504
1403638520477829376
1403638520527829504
1403638520577829376
1403638520627829504
1403638520677829376
1403638520727829504
1403638520777829376
1403638520827829504
1403638520877829376
1403638520927829504
1403638520977829376
1403638521027829504
1403638521077829376
1403638521127829504
1403638521177829376
1403638521227829504
1403638521277829376
1403638521327829504
1403638521377829376
1403638521427829504
1403638521477829376
1403638521527829504
1403638521577829376
1403638521627829504
1403638521677829376
1403638521727829504
1403638521777829376
1403638521827829504
1403638521877829376
1403638521927829504
1403638521977829376
1403638522027829504
1403638522077829376
1403638522127829504
1403638522177829376
1403638522227829504
1403638522277829376
1403638522327829504
1403638522377829376
1403638522427829504
1403638522477829376
1403638522527829504
1403638522577829376
1403638522627829504
1403638522677829376
1403638522727829504
1403638522777829376
1403638522827829504
1403638522877829376
1403638522927829504
1403638522977829376
1403638523027829504
1403638523077829376
1403638523127829504
1403638523177829376
1403638523227829504
1403638523277829376
1403638523327829504
1403638523377829376
1403638523427829504
1403638523477829376
1403638523527829504
1403638523577829376
1403638523627829504
1403638523677829376
1403638523727829504
1403638523777829376
1403638523827829504
1403638523877829376
1403638523927829504
1403638523977829376
1403638524027829504
1403638524077829376
1403638524127829504
1403638524177829376
1403638524227829504
1403638524277829376
1403638524327829504
1403638524377829376
1403638524427829504
1403638524477829376
1403638524527829504
1403638524577829376
1403638524627829504
1403638524677829376
1403638524727829504
1403638524777829376
1403638524827829504
1403638524877829376
1403638524927829504
1403638524977829376
1403638525027829504
1403638525077829376
1403638525127829504
1403638525177829376
1403638525227829504
1403638525277829376
1403638525327829504
1403638525377829376
1403638525427829504
1403638525477829376
1403638525527829504
1403638525577829376
1403638525627829504
1403638525677829376
1403638525727829504
1403638525777829376
1403638525827829504
1403638525877829376
1403638525927829504
1403638525977829376
1403638526027829504
1403638526077829376
1403638526127829504
1403638526177829376
1403638526227829504
1403638526277829376
1403638526327829504
1403638526377829376
1403638526427829504
1403638526477829376
1403638526527829504
1403638526577829376
1403638526627829504
1403638526677829376
1403638526727829504
1403638526777829376
1403638526827829504
1403638526877829376
1403638526927829504
1403638526977829376
1403638527027829504
1403638527077829376
1403638527127829504
1403638527177829376
1403638527227829504
1403638527277829376
1403638527327829504
1403638527377829376
1403638527427829504
1403638527477829376
1403638527527829504
1403638527577829376
1403638527627829504
1403638527677829376
1403638527727829504
1403638527777829376
1403638527827829504
1403638527877829376
1403638527927829504
1403638527977829376
1403638528027829504
1403638528077829376
1403638528127829504
1403638528177829376
1403638528227829504
1403638528277829376
1403638528327829504
1403638528377829376
1403638528427829504
1403638528477829376
1403638528527829504
1403638528577829376
1403638528627829504
1403638528677829376
1403638528727829504
1403638528777829376
1403638528827829504
1403638528877829376
1403638528927829504
1403638528977829376
1403638529027829504
1403638529077829376
1403638529127829504
1403638529177829376
1403638529227829504
1403638529277829376
1403638529327829504
1403638529377829376
1403638529427829504
1403638529477829376
1403638529527829504
1403638529577829376
1403638529627829504
1403638529677829376
1403638529727829504
1403638529777829376
1403638529827829504
1403638529877829376
1403638529927829504
1403638529977829376
1403638530027829504
1403638530077829376
1403638530127829504
1403638530177829376
1403638530227829504
1403638530277829376
1403638530327829504
1403638530377829376
1403638530427829504
1403638530477829376
1403638530527829504
1403638530577829376
1403638530627829504
1403638530677829376
1403638530727829504
1403638530777829376
1403638530827829504
1403638530877829376
1403638530927829504
1403638530977829376
1403638531027829504
1403638531077829376
1403638531127829504
1403638531177829376
1403638531227829504
1403638531277829376
1403638531327829504
1403638531377829376
1403638531427829504
1403638531477829376
1403638531527829504
1403638531577829376
1403638531627829504
1403638531677829376
1403638531727829504
1403638531777829376
1403638531827829504
1403638531877829376
1403638531927829504
1403638531977829376
1403638532027829504
1403638532077829376
1403638532127829504
1403638532177829376
1403638532227829504
1403638532277829376
1403638532327829504
1403638532377829376
1403638532427829504
1403638532477829376
1403638532527829504
1403638532577829376
1403638532627829504
1403638532677829376
1403638532727829504
1403638532777829376
1403638532827829504
1403638532877829376
1403638532927829504
1403638532977829376
1403638533027829504
1403638533077829376
1403638533127829504
1403638533177829376
1403638533227829504
1403638533277829376
1403638533327829504
1403638533377829376
1403638533427829504
1403638533477829376
1403638533527829504
1403638533577829376
1403638533627829504
1403638533677829376
1403638533727829504
1403638533777829376
1403638533827829504
1403638533877829376
1403638533927829504
1403638533977829376
1403638534027829504
1403638534077829376
1403638534127829504
1403638534177829376
1403638534227829504
1403638534277829376
1403638534327829504
1403638534377829376
1403638534427829504
1403638534477829376
1403638534527829504
1403638534577829376
1403638534627829504
1403638534677829376
1403638534727829504
1403638534777829376
1403638534827829504
1403638534877829376
1403638534927829504
1403638534977829376
1403638535027829504
1403638535077829376
1403638535127829504
1403638535177829376
1403638535227829504
1403638535277829376
1403638535327829504
1403638535377829376
1403638535427829504
1403638535477829376
1403638535527829504
1403638535577829376
1403638535627829504
1403638535677829376
1403638535727829504
1403638535777829376
1403638535827829504
1403638535877829376
1403638535927829504
1403638535977829376
1403638536027829504
1403638536077829376
1403638536127829504
1403638536177829376
1403638536227829504
1403638536277829376
1403638536327829504
1403638536377829376
1403638536427829504
1403638536477829376
1403638536527829504
1403638536577829376
1403638536627829504
1403638536677829376
1403638536727829504
1403638536777829376
1403638536827829504
1403638536877829376
1403638536927829504
1403638536977829376
1403638537027829504
1403638537077829376
1403638537127829504
1403638537177829376
1403638537227829504
1403638537277829376
1403638537327829504
1403638537377829376
1403638537427829504
1403638537477829376
1403638537527829504
1403638537577829376
1403638537627829504
1403638537677829376
1403638537727829504
1403638537777829376
1403638537827829504
1403638537877829376
1403638537927829504
1403638537977829376
1403638538027829504
1403638538077829376
1403638538127829504
1403638538177829376
1403638538227829504
1403638538277829376
1403638538327829504
1403638538377829376
1403638538427829504
1403638538477829376
1403638538527829504
1403638538577829376
1403638538627829504
1403638538677829376
1403638538727829504
1403638538777829376
1403638538827829504
1403638538877829376
1403638538927829504
1403638538977829376
1403638539027829504
1403638539077829376
1403638539127829504
1403638539177829376
1403638539227829504
1403638539277829376
1403638539327829504
1403638539377829376
1403638539427829504
1403638539477829376
1403638539527829504
1403638539577829376
1403638539627829504
1403638539677829376
1403638539727829504
1403638539777829376
1403638539827829504
1403638539877829376
1403638539927829504
1403638539977829376
1403638540027829504
1403638540077829376
1403638540127829504
1403638540177829376
1403638540227829504
1403638540277829376
1403638540327829504
1403638540377829376
1403638540427829504
1403638540477829376
1403638540527829504
1403638540577829376
1403638540627829504
1403638540677829376
1403638540727829504
1403638540777829376
1403638540827829504
1403638540877829376
1403638540927829504
1403638540977829376
1403638541027829504
1403638541077829376
1403638541127829504
1403638541177829376
1403638541227829504
1403638541277829376
1403638541327829504
1403638541377829376
1403638541427829504
1403638541477829376
1403638541527829504
1403638541577829376
1403638541627829504
1403638541677829376
1403638541727829504
1403638541777829376
1403638541827829504
1403638541877829376
1403638541927829504
1403638541977829376
1403638542027829504
1403638542077829376
1403638542127829504
1403638542177829376
1403638542227829504
1403638542277829376
1403638542327829504
1403638542377829376
1403638542427829504
1403638542477829376
1403638542527829504
1403638542577829376
1403638542627829504
1403638542677829376
1403638542727829504
1403638542777829376
1403638542827829504
1403638542877829376
1403638542927829504
1403638542977829376
1403638543027829504
1403638543077829376
1403638543127829504
1403638543177829376
1403638543227829504
1403638543277829376
1403638543327829504
1403638543377829376
1403638543427829504
1403638543477829376
1403638543527829504
1403638543577829376
1403638543627829504
1403638543677829376
1403638543727829504
1403638543777829376
1403638543827829504
1403638543877829376
1403638543927829504
1403638543977829376
1403638544027829504
1403638544077829376
1403638544127829504
1403638544177829376
1403638544227829504
1403638544277829376
1403638544327829504
1403638544377829376
1403638544427829504
1403638544477829376
1403638544527829504
1403638544577829376
1403638544627829504
1403638544677829376
1403638544727829504
1403638544777829376
1403638544827829504
1403638544877829376
1403638544927829504
1403638544977829376
1403638545027829504
1403638545077829376
1403638545127829504
1403638545177829376
1403638545227829504
1403638545277829376
1403638545327829504
1403638545377829376
1403638545427829504
1403638545477829376
1403638545527829504
1403638545577829376
1403638545627829504
1403638545677829376
1403638545727829504
1403638545777829376
1403638545827829504
1403638545877829376
1403638545927829504
1403638545977829376
1403638546027829504
1403638546077829376
1403638546127829504
1403638546177829376
1403638546227829504
1403638546277829376
1403638546327829504
1403638546377829376
1403638546427829504
1403638546477829376
1403638546527829504
1403638546577829376
1403638546627829504
1403638546677829376
1403638546727829504
1403638546777829376
1403638546827829504
1403638546877829376
1403638546927829504
1403638546977829376
1403638547027829504
1403638547077829376
1403638547127829504
1403638547177829376
1403638547227829504
1403638547277829376
1403638547327829504
1403638547377829376
1403638547427829504
1403638547477829376
1403638547527829504
1403638547577829376
1403638547627829504
1403638547677829376
1403638547727829504
1403638547777829376
1403638547827829504
1403638547877829376
1403638547927829504
1403638547977829376
1403638548027829504
1403638548077829376
1403638548127829504
1403638548177829376
1403638548227829504
1403638548277829376
1403638548327829504
1403638548377829376
1403638548427829504
1403638548477829376
1403638548527829504
1403638548577829376
1403638548627829504
1403638548677829376
1403638548727829504
1403638548777829376
1403638548827829504
1403638548877829376
1403638548927829504
1403638548977829376
1403638549027829504
1403638549077829376
1403638549127829504
1403638549177829376
1403638549227829504
1403638549277829376
1403638549327829504
1403638549377829376
1403638549427829504
1403638549477829376
1403638549527829504
1403638549577829376
1403638549627829504
1403638549677829376
1403638549727829504
1403638549777829376
1403638549827829504
1403638549877829376
1403638549927829504
1403638549977829376
1403638550027829504
1403638550077829376
1403638550127829504
1403638550177829376
1403638550227829504
1403638550277829376
1403638550327829504
1403638550377829376
1403638550427829504
1403638550477829376
1403638550527829504
1403638550577829376
1403638550627829504
1403638550677829376
1403638550727829504
1403638550777829376
1403638550827829504
1403638550877829376
1403638550927829504
1403638550977829376
1403638551027829504
1403638551077829376
1403638551127829504
1403638551177829376
1403638551227829504
1403638551277829376
1403638551327829504
1403638551377829376
1403638551427829504
1403638551477829376
1403638551527829504
1403638551577829376
1403638551627829504
1403638551677829376
1403638551727829504
1403638551777829376
1403638551827829504
1403638551877829376
1403638551927829504
1403638551977829376
1403638552027829504
1403638552077829376
1403638552127829504
1403638552177829376
1403638552227829504
1403638552277829376
1403638552327829504
1403638552377829376
1403638552427829504
1403638552477829376
1403638552527829504
1403638552577829376
1403638552627829504
1403638552677829376
1403638552727829504
1403638552777829376
1403638552827829504
1403638552877829376
1403638552927829504
1403638552977829376
1403638553027829504
1403638553077829376
1403638553127829504
1403638553177829376
1403638553227829504
1403638553277829376
1403638553327829504
1403638553377829376
1403638553427829504
1403638553477829376
1403638553527829504
1403638553577829376
1403638553627829504
1403638553677829376
1403638553727829504
1403638553777829376
1403638553827829504
1403638553877829376
1403638553927829504
1403638553977829376
1403638554027829504
1403638554077829376
1403638554127829504
1403638554177829376
1403638554227829504
1403638554277829376
1403638554327829504
1403638554377829376
1403638554427829504
1403638554477829376
1403638554527829504
1403638554577829376
1403638554627829504
1403638554677829376
1403638554727829504
1403638554777829376
1403638554827829504
1403638554877829376
1403638554927829504
1403638554977829376
1403638555027829504
1403638555077829376
1403638555127829504
1403638555177829376
1403638555227829504
1403638555277829376
1403638555327829504
1403638555377829376
1403638555427829504
1403638555477829376
1403638555527829504
1403638555577829376
1403638555627829504
1403638555677829376
1403638555727829504
1403638555777829376
1403638555827829504
1403638555877829376
1403638555927829504
1403638555977829376
1403638556027829504
1403638556077829376
1403638556127829504
1403638556177829376
1403638556227829504
1403638556277829376
1403638556327829504
1403638556377829376
1403638556427829504
1403638556477829376
1403638556527829504
1403638556577829376
1403638556627829504
1403638556677829376
1403638556727829504
1403638556777829376
1403638556827829504
1403638556877829376
1403638556927829504
1403638556977829376
1403638557027829504
1403638557077829376
1403638557127829504
1403638557177829376
1403638557227829504
1403638557277829376
1403638557327829504
1403638557377829376
1403638557427829504
1403638557477829376
1403638557527829504
1403638557577829376
1403638557627829504
1403638557677829376
1403638557727829504
1403638557777829376
1403638557827829504
1403638557877829376
1403638557927829504
1403638557977829376
1403638558027829504
1403638558077829376
1403638558127829504
1403638558177829376
1403638558227829504
1403638558277829376
1403638558327829504
1403638558377829376
1403638558427829504
1403638558477829376
1403638558527829504
1403638558577829376
1403638558627829504
1403638558677829376
1403638558727829504
1403638558777829376
1403638558827829504
1403638558877829376
1403638558927829504
1403638558977829376
1403638559027829504
1403638559077829376
1403638559127829504
1403638559177829376
1403638559227829504
1403638559277829376
1403638559327829504
1403638559377829376
1403638559427829504
1403638559477829376
1403638559527829504
1403638559577829376
1403638559627829504
1403638559677829376
1403638559727829504
1403638559777829376
1403638559827829504
1403638559877829376
1403638559927829504
1403638559977829376
1403638560027829504
1403638560077829376
1403638560127829504
1403638560177829376
1403638560227829504
1403638560277829376
1403638560327829504
1403638560377829376
1403638560427829504
1403638560477829376
1403638560527829504
1403638560577829376
1403638560627829504
1403638560677829376
1403638560727829504
1403638560777829376
1403638560827829504
1403638560877829376
1403638560927829504
1403638560977829376
1403638561027829504
1403638561077829376
1403638561127829504
1403638561177829376
1403638561227829504
1403638561277829376
1403638561327829504
1403638561377829376
1403638561427829504
1403638561477829376
1403638561527829504
1403638561577829376
1403638561627829504
1403638561677829376
1403638561727829504
1403638561777829376
1403638561827829504
1403638561877829376
1403638561927829504
1403638561977829376
1403638562027829504
1403638562077829376
1403638562127829504
1403638562177829376
1403638562227829504
1403638562277829376
1403638562327829504
1403638562377829376
1403638562427829504
1403638562477829376
1403638562527829504
1403638562577829376
1403638562627829504
1403638562677829376
1403638562727829504
1403638562777829376
1403638562827829504
1403638562877829376
1403638562927829504
1403638562977829376
1403638563027829504
1403638563077829376
1403638563127829504
1403638563177829376
1403638563227829504
1403638563277829376
1403638563327829504
1403638563377829376
1403638563427829504
1403638563477829376
1403638563527829504
1403638563577829376
1403638563627829504
1403638563677829376
1403638563727829504
1403638563777829376
1403638563827829504
1403638563877829376
1403638563927829504
1403638563977829376
1403638564027829504
1403638564077829376
1403638564127829504
1403638564177829376
1403638564227829504
1403638564277829376
1403638564327829504
1403638564377829376
1403638564427829504
1403638564477829376
1403638564527829504
1403638564577829376
1403638564627829504
1403638564677829376
1403638564727829504
1403638564777829376
1403638564827829504
1403638564877829376
1403638564927829504
1403638564977829376
1403638565027829504
1403638565077829376
1403638565127829504
1403638565177829376
1403638565227829504
1403638565277829376
1403638565327829504
1403638565377829376
1403638565427829504
1403638565477829376
1403638565527829504
1403638565577829376
1403638565627829504
1403638565677829376
1403638565727829504
1403638565777829376
1403638565827829504
1403638565877829376
1403638565927829504
1403638565977829376
1403638566027829504
1403638566077829376
1403638566127829504
1403638566177829376
1403638566227829504
1403638566277829376
1403638566327829504
1403638566377829376
1403638566427829504
1403638566477829376
1403638566527829504
1403638566577829376
1403638566627829504
1403638566677829376
1403638566727829504
1403638566777829376
1403638566827829504
1403638566877829376
1403638566927829504
1403638566977829376
1403638567027829504
1403638567077829376
1403638567127829504
1403638567177829376
1403638567227829504
1403638567277829376
1403638567327829504
1403638567377829376
1403638567427829504
1403638567477829376
1403638567527829504
1403638567577829376
1403638567627829504
1403638567677829376
1403638567727829504
1403638567777829376
1403638567827829504
1403638567877829376
1403638567927829504
1403638567977829376
1403638568027829504
1403638568077829376
1403638568127829504
1403638568177829376
1403638568227829504
1403638568277829376
1403638568327829504
1403638568377829376
1403638568427829504
1403638568477829376
1403638568527829504
1403638568577829376
1403638568627829504
1403638568677829376
1403638568727829504
1403638568777829376
1403638568827829504
1403638568877829376
1403638568927829504
1403638568977829376
1403638569027829504
1403638569077829376
1403638569127829504
1403638569177829376
1403638569227829504
1403638569277829376
1403638569327829504
1403638569377829376
1403638569427829504
1403638569477829376
1403638569527829504
1403638569577829376
1403638569627829504
1403638569677829376
1403638569727829504
1403638569777829376
1403638569827829504
1403638569877829376
1403638569927829504
1403638569977829376
1403638570027829504
1403638570077829376
1403638570127829504
1403638570177829376
1403638570227829504
1403638570277829376
1403638570327829504
1403638570377829376
1403638570427829504
1403638570477829376
1403638570527829504
1403638570577829376
1403638570627829504
1403638570677829376
1403638570727829504
1403638570777829376
1403638570827829504
1403638570877829376
1403638570927829504
1403638570977829376
1403638571027829504
1403638571077829376
1403638571127829504
1403638571177829376
1403638571227829504
1403638571277829376
1403638571327829504
1403638571377829376
1403638571427829504
1403638571477829376
1403638571527829504
1403638571577829376
1403638571627829504
1403638571677829376
1403638571727829504
1403638571777829376
1403638571827829504
1403638571877829376
1403638571927829504
1403638571977829376
1403638572027829504
1403638572077829376
1403638572127829504
1403638572177829376
1403638572227829504
1403638572277829376
1403638572327829504
1403638572377829376
1403638572427829504
1403638572477829376
1403638572527829504
1403638572577829376
1403638572627829504
1403638572677829376
1403638572727829504
1403638572777829376
1403638572827829504
1403638572877829376
1403638572927829504
1403638572977829376
1403638573027829504
1403638573077829376
1403638573127829504
1403638573177829376
1403638573227829504
1403638573277829376
1403638573327829504
1403638573377829376
1403638573427829504
1403638573477829376
1403638573527829504
1403638573577829376
1403638573627829504
1403638573677829376
1403638573727829504
1403638573777829376
1403638573827829504
1403638573877829376
1403638573927829504
1403638573977829376
1403638574027829504
1403638574077829376
1403638574127829504
1403638574177829376
1403638574227829504
1403638574277829376
1403638574327829504
1403638574377829376
1403638574427829504
1403638574477829376
1403638574527829504
1403638574577829376
1403638574627829504
1403638574677829376
1403638574727829504
1403638574777829376
1403638574827829504
1403638574877829376
1403638574927829504
1403638574977829376
1403638575027829504
1403638575077829376
1403638575127829504
1403638575177829376
1403638575227829504
1403638575277829376
1403638575327829504
1403638575377829376
1403638575427829504
1403638575477829376
1403638575527829504
1403638575577829376
1403638575627829504
1403638575677829376
1403638575727829504
1403638575777829376
1403638575827829504
1403638575877829376
1403638575927829504
1403638575977829376
1403638576027829504
1403638576077829376
1403638576127829504
1403638576177829376
1403638576227829504
1403638576277829376
1403638576327829504
1403638576377829376
1403638576427829504
1403638576477829376
1403638576527829504
1403638576577829376
1403638576627829504
1403638576677829376
1403638576727829504
1403638576777829376
1403638576827829504
1403638576877829376
1403638576927829504
1403638576977829376
1403638577027829504
1403638577077829376
1403638577127829504
1403638577177829376
1403638577227829504
1403638577277829376
1403638577327829504
1403638577377829376
1403638577427829504
1403638577477829376
1403638577527829504
1403638577577829376
1403638577627829504
1403638577677829376
1403638577727829504
1403638577777829376
1403638577827829504
1403638577877829376
1403638577927829504
1403638577977829376
1403638578027829504
1403638578077829376
1403638578127829504
1403638578177829376
1403638578227829504
1403638578277829376
1403638578327829504
1403638578377829376
1403638578427829504
1403638578477829376
1403638578527829504
1403638578577829376
1403638578627829504
1403638578677829376
1403638578727829504
1403638578777829376
1403638578827829504
1403638578877829376
1403638578927829504
1403638578977829376
1403638579027829504
1403638579077829376
1403638579127829504
1403638579177829376
1403638579227829504
1403638579277829376
1403638579327829504
1403638579377829376
1403638579427829504
1403638579477829376
1403638579527829504
1403638579577829376
1403638579627829504
1403638579677829376
1403638579727829504
1403638579777829376
1403638579827829504
1403638579877829376
1403638579927829504
1403638579977829376
1403638580027829504
1403638580077829376
1403638580127829504
1403638580177829376
1403638580227829504
1403638580277829376
1403638580327829504
1403638580377829376
1403638580427829504
1403638580477829376
1403638580527829504
1403638580577829376
1403638580627829504
1403638580677829376
1403638580727829504
1403638580777829376
1403638580827829504
1403638580877829376
1403638580927829504
1403638580977829376
1403638581027829504
1403638581077829376
1403638581127829504
1403638581177829376
1403638581227829504
1403638581277829376
1403638581327829504
1403638581377829376
1403638581427829504
1403638581477829376
1403638581527829504
1403638581577829376
1403638581627829504
1403638581677829376
1403638581727829504
1403638581777829376
1403638581827829504
1403638581877829376
1403638581927829504
1403638581977829376
1403638582027829504
1403638582077829376
1403638582127829504
1403638582177829376
1403638582227829504
1403638582277829376
1403638582327829504
1403638582377829376
1403638582427829504
1403638582477829376
1403638582527829504
1403638582577829376
1403638582627829504
1403638582677829376
1403638582727829504
1403638582777829376
1403638582827829504
1403638582877829376
1403638582927829504
1403638582977829376
1403638583027829504
1403638583077829376
1403638583127829504
1403638583177829376
1403638583227829504
1403638583277829376
1403638583327829504
1403638583377829376
1403638583427829504
1403638583477829376
1403638583527829504
1403638583577829376
1403638583627829504
1403638583677829376
1403638583727829504
1403638583777829376
1403638583827829504
1403638583877829376
1403638583927829504
1403638583977829376
1403638584027829504
1403638584077829376
1403638584127829504
1403638584177829376
1403638584227829504
1403638584277829376
1403638584327829504
1403638584377829376
1403638584427829504
1403638584477829376
1403638584527829504
1403638584577829376
1403638584627829504
1403638584677829376
1403638584727829504
1403638584777829376
1403638584827829504
1403638584877829376
1403638584927829504
1403638584977829376
1403638585027829504
1403638585077829376
1403638585127829504
1403638585177829376
1403638585227829504
1403638585277829376
1403638585327829504
1403638585377829376
1403638585427829504
1403638585477829376
1403638585527829504
1403638585577829376
1403638585627829504
1403638585677829376
1403638585727829504
1403638585777829376
1403638585827829504
1403638585877829376
1403638585927829504
1403638585977829376
1403638586027829504
1403638586077829376
1403638586127829504
1403638586177829376
1403638586227829504
1403638586277829376
1403638586327829504
1403638586377829376
1403638586427829504
1403638586477829376
1403638586527829504
1403638586577829376
1403638586627829504
1403638586677829376
1403638586727829504
1403638586777829376
1403638586827829504
1403638586877829376
1403638586927829504
1403638586977829376
1403638587027829504
1403638587077829376
1403638587127829504
1403638587177829376
1403638587227829504
1403638587277829376
1403638587327829504
1403638587377829376
1403638587427829504
1403638587477829376
1403638587527829504
1403638587577829376
1403638587627829504
1403638587677829376
1403638587727829504
1403638587777829376
1403638587827829504
1403638587877829376
1403638587927829504
1403638587977829376
1403638588027829504
1403638588077829376
1403638588127829504
1403638588177829376
1403638588227829504
1403638588277829376
1403638588327829504
1403638588377829376
1403638588427829504
1403638588477829376
1403638588527829504
1403638588577829376
1403638588627829504
1403638588677829376
1403638588727829504
1403638588777829376
1403638588827829504
1403638588877829376
1403638588927829504
1403638588977829376
1403638589027829504
1403638589077829376
1403638589127829504
1403638589177829376
1403638589227829504
1403638589277829376
1403638589327829504
1403638589377829376
1403638589427829504
1403638589477829376
1403638589527829504
1403638589577829376
1403638589627829504
1403638589677829376
1403638589727829504
1403638589777829376
1403638589827829504
1403638589877829376
1403638589927829504
1403638589977829376
1403638590027829504
1403638590077829376
1403638590127829504
1403638590177829376
1403638590227829504
1403638590277829376
1403638590327829504
1403638590377829376
1403638590427829504
1403638590477829376
1403638590527829504
1403638590577829376
1403638590627829504
1403638590677829376
1403638590727829504
1403638590777829376
1403638590827829504
1403638590877829376
1403638590927829504
1403638590977829376
1403638591027829504
1403638591077829376
1403638591127829504
1403638591177829376
1403638591227829504
1403638591277829376
1403638591327829504
1403638591377829376
1403638591427829504
1403638591477829376
1403638591527829504
1403638591577829376
1403638591627829504
1403638591677829376
1403638591727829504
1403638591777829376
1403638591827829504
1403638591877829376
1403638591927829504
1403638591977829376
1403638592027829504
1403638592077829376
1403638592127829504
1403638592177829376
1403638592227829504
1403638592277829376
1403638592327829504
1403638592377829376
1403638592427829504
1403638592477829376
1403638592527829504
1403638592577829376
1403638592627829504
1403638592677829376
1403638592727829504
1403638592777829376
1403638592827829504
1403638592877829376
1403638592927829504
1403638592977829376
1403638593027829504
1403638593077829376
1403638593127829504
1403638593177829376
1403638593227829504
1403638593277829376
1403638593327829504
1403638593377829376
1403638593427829504
1403638593477829376
1403638593527829504
1403638593577829376
1403638593627829504
1403638593677829376
1403638593727829504
1403638593777829376
1403638593827829504
1403638593877829376
1403638593927829504
1403638593977829376
1403638594027829504
1403638594077829376
1403638594127829504
1403638594177829376
1403638594227829504
1403638594277829376
1403638594327829504
1403638594377829376
1403638594427829504
1403638594477829376
1403638594527829504
1403638594577829376
1403638594627829504
1403638594677829376
1403638594727829504
1403638594777829376
1403638594827829504
1403638594877829376
1403638594927829504
1403638594977829376
1403638595027829504
1403638595077829376
1403638595127829504
1403638595177829376
1403638595227829504
1403638595277829376
1403638595327829504
1403638595377829376
1403638595427829504
1403638595477829376
1403638595527829504
1403638595577829376
1403638595627829504
1403638595677829376
1403638595727829504
1403638595777829376
1403638595827829504
1403638595877829376
1403638595927829504
1403638595977829376
1403638596027829504
1403638596077829376
1403638596127829504
1403638596177829376
1403638596227829504
1403638596277829376
1403638596327829504
1403638596377829376
1403638596427829504
1403638596477829376
1403638596527829504
1403638596577829376
1403638596627829504
1403638596677829376
1403638596727829504
1403638596777829376
1403638596827829504
1403638596877829376
1403638596927829504
1403638596977829376
1403638597027829504
1403638597077829376
1403638597127829504
1403638597177829376
1403638597227829504
1403638597277829376
1403638597327829504
1403638597377829376
1403638597427829504
1403638597477829376
1403638597527829504
1403638597577829376
1403638597627829504
1403638597677829376
1403638597727829504
1403638597777829376
1403638597827829504
1403638597877829376
1403638597927829504
1403638597977829376
1403638598027829504
1403638598077829376
1403638598127829504
1403638598177829376
1403638598227829504
1403638598277829376
1403638598327829504
1403638598377829376
1403638598427829504
1403638598477829376
1403638598527829504
1403638598577829376
1403638598627829504
1403638598677829376
1403638598727829504
1403638598777829376
1403638598827829504
1403638598877829376
1403638598927829504
1403638598977829376
1403638599027829504
1403638599077829376
1403638599127829504
1403638599177829376
1403638599227829504
1403638599277829376
1403638599327829504
1403638599377829376
1403638599427829504
1403638599477829376
1403638599527829504
1403638599577829376
1403638599627829504
1403638599677829376
1403638599727829504
1403638599777829376
1403638599827829504
1403638599877829376
1403638599927829504
1403638599977829376
1403638600027829504
1403638600077829376
1403638600127829504
1403638600177829376
1403638600227829504
1403638600277829376
1403638600327829504
1403638600377829376
1403638600427829504
1403638600477829376
1403638600527829504
1403638600577829376
1403638600627829504
1403638600677829376
1403638600727829504
1403638600777829376
1403638600827829504
1403638600877829376
1403638600927829504
1403638600977829376
1403638601027829504
1403638601077829376
1403638601127829504
1403638601177829376
1403638601227829504
1403638601277829376
1403638601327829504
1403638601377829376
1403638601427829504
1403638601477829376
1403638601527829504
1403638601577829376
1403638601627829504
1403638601677829376
1403638601727829504
1403638601777829376
1403638601827829504
1403638601877829376
1403638601927829504
1403638601977829376
1403638602027829504
1403638602077829376
1403638602127829504
1403638602177829376
1403638602227829504
1403638602277829376
1403638602327829504
1403638602377829376
1403638602427829504
1403638602477829376
1403638602527829504
1403638602577829376
1403638602627829504
1403638602677829376
1403638602727829504
1403638602777829376
1403638602827829504
1403638602877829376
1403638602927829504
1403638602977829376
1403638603027829504
1403638603077829376
1403638603127829504
1403638603177829376
1403638603227829504
1403638603277829376
1403638603327829504
1403638603377829376
1403638603427829504
1403638603477829376
1403638603527829504
1403638603577829376
1403638603627829504
1403638603677829376
1403638603727829504
1403638603777829376
1403638603827829504
1403638603877829376
1403638603927829504
1403638603977829376
1403638604027829504
1403638604077829376
1403638604127829504
1403638604177829376
1403638604227829504
1403638604277829376
1403638604327829504
1403638604377829376
1403638604427829504
1403638604477829376
1403638604527829504
1403638604577829376
1403638604627829504
1403638604677829376
1403638604727829504
1403638604777829376
1403638604827829504
1403638604877829376
1403638604927829504
1403638604977829376
1403638605027829504
1403638605077829376
1403638605127829504
1403638605177829376
1403638605227829504
1403638605277829376
1403638605327829504
1403638605377829376
1403638605427829504
1403638605477829376
1403638605527829504
1403638605577829376
1403638605627829504
1403638605677829376
1403638605727829504
1403638605777829376
1403638605827829504
1403638605877829376
1403638605927829504
1403638605977829376
1403638606027829504
1403638606077829376
1403638606127829504
1403638606177829376
1403638606227829504
1403638606277829376
1403638606327829504
1403638606377829376
1403638606427829504
1403638606477829376
1403638606527829504
1403638606577829376
1403638606627829504
1403638606677829376
1403638606727829504
1403638606777829376
1403638606827829504
1403638606877829376
1403638606927829504
1403638606977829376
1403638607027829504
1403638607077829376
1403638607127829504
1403638607177829376
1403638607227829504
1403638607277829376
1403638607327829504
1403638607377829376
1403638607427829504
1403638607477829376
1403638607527829504
1403638607577829376
1403638607627829504
1403638607677829376
1403638607727829504
1403638607777829376
1403638607827829504
1403638607877829376
1403638607927829504
1403638607977829376
1403638608027829504
1403638608077829376
1403638608127829504
1403638608177829376
1403638608227829504
1403638608277829376
1403638608327829504
1403638608377829376
1403638608427829504
1403638608477829376
1403638608527829504
1403638608577829376
1403638608627829504
1403638608677829376
1403638608727829504
1403638608777829376
1403638608827829504
1403638608877829376
1403638608927829504
1403638608977829376
1403638609027829504
1403638609077829376
1403638609127829504
1403638609177829376
1403638609227829504
1403638609277829376
1403638609327829504
1403638609377829376
1403638609427829504
1403638609477829376
1403638609527829504
1403638609577829376
1403638609627829504
1403638609677829376
1403638609727829504
1403638609777829376
1403638609827829504
1403638609877829376
1403638609927829504
1403638609977829376
1403638610027829504
1403638610077829376
1403638610127829504
1403638610177829376
1403638610227829504
1403638610277829376
1403638610327829504
1403638610377829376
1403638610427829504
1403638610477829376
1403638610527829504
1403638610577829376
1403638610627829504
1403638610677829376
1403638610727829504
1403638610777829376
1403638610827829504
1403638610877829376
1403638610927829504
1403638610977829376
1403638611027829504
1403638611077829376
1403638611127829504
1403638611177829376
1403638611227829504
1403638611277829376
1403638611327829504
1403638611377829376
1403638611427829504
1403638611477829376
1403638611527829504
1403638611577829376
1403638611627829504
1403638611677829376
1403638611727829504
1403638611777829376
1403638611827829504
1403638611877829376
1403638611927829504
1403638611977829376
1403638612027829504
1403638612077829376
1403638612127829504
1403638612177829376
1403638612227829504
1403638612277829376
1403638612327829504
1403638612377829376
1403638612427829504
1403638612477829376
1403638612527829504
1403638612577829376
1403638612627829504
1403638612677829376
1403638612727829504
1403638612777829376
1403638612827829504
1403638612877829376
1403638612927829504
1403638612977829376
1403638613027829504
1403638613077829376
1403638613127829504
1403638613177829376
1403638613227829504
1403638613277829376
1403638613327829504
1403638613377829376
1403638613427829504
1403638613477829376
1403638613527829504
1403638613577829376
1403638613627829504
1403638613677829376
1403638613727829504
1403638613777829376
1403638613827829504
1403638613877829376
1403638613927829504
1403638613977829376
1403638614027829504
1403638614077829376
1403638614127829504
1403638614177829376
1403638614227829504
1403638614277829376
1403638614327829504
1403638614377829376
1403638614427829504
1403638614477829376
1403638614527829504
1403638614577829376
1403638614627829504
1403638614677829376
1403638614727829504
1403638614777829376
1403638614827829504
1403638614877829376
1403638614927829504
1403638614977829376
1403638615027829504
1403638615077829376
1403638615127829504
1403638615177829376
1403638615227829504
1403638615277829376
1403638615327829504
1403638615377829376
1403638615427829504
1403638615477829376
1403638615527829504
1403638615577829376
1403638615627829504
1403638615677829376
1403638615727829504
1403638615777829376
1403638615827829504
1403638615877829376
1403638615927829504
1403638615977829376
1403638616027829504
1403638616077829376
1403638616127829504
1403638616177829376
1403638616227829504
1403638616277829376
1403638616327829504
1403638616377829376
1403638616427829504
1403638616477829376
1403638616527829504
1403638616577829376
1403638616627829504
1403638616677829376
1403638616727829504
1403638616777829376
1403638616827829504
1403638616877829376
1403638616927829504
1403638616977829376
1403638617027829504
1403638617077829376
1403638617127829504
1403638617177829376
1403638617227829504
1403638617277829376
1403638617327829504
1403638617377829376
1403638617427829504
1403638617477829376
1403638617527829504
1403638617577829376
1403638617627829504
1403638617677829376
1403638617727829504
1403638617777829376
1403638617827829504
1403638617877829376
1403638617927829504
1403638617977829376
1403638618027829504
1403638618077829376
1403638618127829504
1403638618177829376
1403638618227829504
1403638618277829376
1403638618327829504
1403638618377829376
1403638618427829504
1403638618477829376
1403638618527829504
1403638618577829376
1403638618627829504
1403638618677829376
1403638618727829504
1403638618777829376
1403638618827829504
1403638618877829376
1403638618927829504
1403638618977829376
1403638619027829504
1403638619077829376
1403638619127829504
1403638619177829376
1403638619227829504
1403638619277829376
1403638619327829504
1403638619377829376
1403638619427829504
1403638619477829376
1403638619527829504
1403638619577829376
1403638619627829504
1403638619677829376
1403638619727829504
1403638619777829376
1403638619827829504
1403638619877829376
1403638619927829504
1403638619977829376
1403638620027829504
1403638620077829376
1403638620127829504
1403638620177829376
1403638620227829504
1403638620277829376
1403638620327829504
1403638620377829376
1403638620427829504
1403638620477829376
1403638620527829504
1403638620577829376
1403638620627829504
1403638620677829376
1403638620727829504
1403638620777829376
1403638620827829504
1403638620877829376
1403638620927829504
1403638620977829376
1403638621027829504
1403638621077829376
1403638621127829504
1403638621177829376
1403638621227829504
1403638621277829376
1403638621327829504
1403638621377829376
1403638621427829504
1403638621477829376
1403638621527829504
1403638621577829376
1403638621627829504
1403638621677829376
1403638621727829504
1403638621777829376
1403638621827829504
1403638621877829376
1403638621927829504
1403638621977829376
1403638622027829504
1403638622077829376
1403638622127829504
1403638622177829376
1403638622227829504
1403638622277829376
1403638622327829504
1403638622377829376
1403638622427829504
1403638622477829376
1403638622527829504
1403638622577829376
1403638622627829504
1403638622677829376
1403638622727829504
1403638622777829376
1403638622827829504
1403638622877829376
1403638622927829504
1403638622977829376
1403638623027829504
1403638623077829376
1403638623127829504
1403638623177829376
1403638623227829504
1403638623277829376
1403638623327829504
1403638623377829376
1403638623427829504
1403638623477829376
1403638623527829504
1403638623577829376
1403638623627829504
1403638623677829376
1403638623727829504
1403638623777829376
1403638623827829504
1403638623877829376
1403638623927829504
1403638623977829376
1403638624027829504
1403638624077829376
1403638624127829504
1403638624177829376
1403638624227829504
1403638624277829376
1403638624327829504
1403638624377829376
1403638624427829504
1403638624477829376
1403638624527829504
1403638624577829376
1403638624627829504
1403638624677829376
1403638624727829504
1403638624777829376
1403638624827829504
1403638624877829376
1403638624927829504
1403638624977829376
1403638625027829504
1403638625077829376
1403638625127829504
1403638625177829376
1403638625227829504
1403638625277829376
1403638625327829504
1403638625377829376
1403638625427829504
1403638625477829376
1403638625527829504
1403638625577829376
1403638625627829504
1403638625677829376
1403638625727829504
1403638625777829376
1403638625827829504
1403638625877829376
1403638625927829504
1403638625977829376
1403638626027829504
1403638626077829376
1403638626127829504
1403638626177829376
1403638626227829504
1403638626277829376
1403638626327829504
1403638626377829376
1403638626427829504
1403638626477829376
1403638626527829504
1403638626577829376
1403638626627829504
1403638626677829376
1403638626727829504
1403638626777829376
1403638626827829504
1403638626877829376
1403638626927829504
1403638626977829376
1403638627027829504
1403638627077829376
1403638627127829504
1403638627177829376
1403638627227829504
1403638627277829376
1403638627327829504
1403638627377829376
1403638627427829504
1403638627477829376
1403638627527829504
1403638627577829376
1403638627627829504
1403638627677829376
1403638627727829504
1403638627777829376
1403638627827829504
1403638627877829376
1403638627927829504
1403638627977829376
1403638628027829504
1403638628077829376
1403638628127829504
1403638628177829376
1403638628227829504
1403638628277829376
1403638628327829504
1403638628377829376
1403638628427829504
1403638628477829376
1403638628527829504
1403638628577829376
1403638628627829504
1403638628677829376
1403638628727829504
1403638628777829376
1403638628827829504
1403638628877829376
1403638628927829504
1403638628977829376
1403638629027829504
1403638629077829376
1403638629127829504
1403638629177829376
1403638629227829504
1403638629277829376
1403638629327829504
1403638629377829376
1403638629427829504
1403638629477829376
1403638629527829504
1403638629577829376
1403638629627829504
1403638629677829376
1403638629727829504
1403638629777829376
1403638629827829504
1403638629877829376
1403638629927829504
1403638629977829376
1403638630027829504
1403638630077829376
1403638630127829504
1403638630177829376
1403638630227829504
1403638630277829376
1403638630327829504
1403638630377829376
1403638630427829504
1403638630477829376
1403638630527829504
1403638630577829376
1403638630627829504
1403638630677829376
1403638630727829504
1403638630777829376
1403638630827829504
1403638630877829376
1403638630927829504
1403638630977829376
1403638631027829504
1403638631077829376
1403638631127829504
1403638631177829376
1403638631227829504
1403638631277829376
1403638631327829504
1403638631377829376
1403638631427829504
1403638631477829376
1403638631527829504
1403638631577829376
1403638631627829504
1403638631677829376
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/V101.txt
================================================
1403715273262142976
1403715273312143104
1403715273362142976
1403715273412143104
1403715273462142976
1403715273512143104
1403715273562142976
1403715273612143104
1403715273662142976
1403715273712143104
1403715273762142976
1403715273812143104
1403715273862142976
1403715273912143104
1403715273962142976
1403715274012143104
1403715274062142976
1403715274112143104
1403715274162142976
1403715274212143104
1403715274262142976
1403715274312143104
1403715274362142976
1403715274412143104
1403715274462142976
1403715274512143104
1403715274562142976
1403715274612143104
1403715274662142976
1403715274712143104
1403715274762142976
1403715274812143104
1403715274862142976
1403715274912143104
1403715274962142976
1403715275012143104
1403715275062142976
1403715275112143104
1403715275162142976
1403715275212143104
1403715275262142976
1403715275312143104
1403715275362142976
1403715275412143104
1403715275462142976
1403715275512143104
1403715275562142976
1403715275612143104
1403715275662142976
1403715275712143104
1403715275762142976
1403715275812143104
1403715275862142976
1403715275912143104
1403715275962142976
1403715276012143104
1403715276062142976
1403715276112143104
1403715276162142976
1403715276212143104
1403715276262142976
1403715276312143104
1403715276362142976
1403715276412143104
1403715276462142976
1403715276512143104
1403715276562142976
1403715276612143104
1403715276662142976
1403715276712143104
1403715276762142976
1403715276812143104
1403715276862142976
1403715276912143104
1403715276962142976
1403715277012143104
1403715277062142976
1403715277112143104
1403715277162142976
1403715277212143104
1403715277262142976
1403715277312143104
1403715277362142976
1403715277412143104
1403715277462142976
1403715277512143104
1403715277562142976
1403715277612143104
1403715277662142976
1403715277712143104
1403715277762142976
1403715277812143104
1403715277862142976
1403715277912143104
1403715277962142976
1403715278012143104
1403715278062142976
1403715278112143104
1403715278162142976
1403715278212143104
1403715278262142976
1403715278312143104
1403715278362142976
1403715278412143104
1403715278462142976
1403715278512143104
1403715278562142976
1403715278612143104
1403715278662142976
1403715278712143104
1403715278762142976
1403715278812143104
1403715278862142976
1403715278912143104
1403715278962142976
1403715279012143104
1403715279062142976
1403715279112143104
1403715279162142976
1403715279212143104
1403715279262142976
1403715279312143104
1403715279362142976
1403715279412143104
1403715279462142976
1403715279512143104
1403715279562142976
1403715279612143104
1403715279662142976
1403715279712143104
1403715279762142976
1403715279812143104
1403715279862142976
1403715279912143104
1403715279962142976
1403715280012143104
1403715280062142976
1403715280112143104
1403715280162142976
1403715280212143104
1403715280262142976
1403715280312143104
1403715280362142976
1403715280412143104
1403715280462142976
1403715280512143104
1403715280562142976
1403715280612143104
1403715280662142976
1403715280712143104
1403715280762142976
1403715280812143104
1403715280862142976
1403715280912143104
1403715280962142976
1403715281012143104
1403715281062142976
1403715281112143104
1403715281162142976
1403715281212143104
1403715281262142976
1403715281312143104
1403715281362142976
1403715281412143104
1403715281462142976
1403715281512143104
1403715281562142976
1403715281612143104
1403715281662142976
1403715281712143104
1403715281762142976
1403715281812143104
1403715281862142976
1403715281912143104
1403715281962142976
1403715282012143104
1403715282062142976
1403715282112143104
1403715282162142976
1403715282212143104
1403715282262142976
1403715282312143104
1403715282362142976
1403715282412143104
1403715282462142976
1403715282512143104
1403715282562142976
1403715282612143104
1403715282662142976
1403715282712143104
1403715282762142976
1403715282812143104
1403715282862142976
1403715282912143104
1403715282962142976
1403715283012143104
1403715283062142976
1403715283112143104
1403715283162142976
1403715283212143104
1403715283262142976
1403715283312143104
1403715283362142976
1403715283412143104
1403715283462142976
1403715283512143104
1403715283562142976
1403715283612143104
1403715283662142976
1403715283712143104
1403715283762142976
1403715283812143104
1403715283862142976
1403715283912143104
1403715283962142976
1403715284012143104
1403715284062142976
1403715284112143104
1403715284162142976
1403715284212143104
1403715284262142976
1403715284312143104
1403715284362142976
1403715284412143104
1403715284462142976
1403715284512143104
1403715284562142976
1403715284612143104
1403715284662142976
1403715284712143104
1403715284762142976
1403715284812143104
1403715284862142976
1403715284912143104
1403715284962142976
1403715285012143104
1403715285062142976
1403715285112143104
1403715285162142976
1403715285212143104
1403715285262142976
1403715285312143104
1403715285362142976
1403715285412143104
1403715285462142976
1403715285512143104
1403715285562142976
1403715285612143104
1403715285662142976
1403715285712143104
1403715285762142976
1403715285812143104
1403715285862142976
1403715285912143104
1403715285962142976
1403715286012143104
1403715286062142976
1403715286112143104
1403715286162142976
1403715286212143104
1403715286262142976
1403715286312143104
1403715286362142976
1403715286412143104
1403715286462142976
1403715286512143104
1403715286562142976
1403715286612143104
1403715286662142976
1403715286712143104
1403715286762142976
1403715286812143104
1403715286862142976
1403715286912143104
1403715286962142976
1403715287012143104
1403715287062142976
1403715287112143104
1403715287162142976
1403715287212143104
1403715287262142976
1403715287312143104
1403715287362142976
1403715287412143104
1403715287462142976
1403715287512143104
1403715287562142976
1403715287612143104
1403715287662142976
1403715287712143104
1403715287762142976
1403715287812143104
1403715287862142976
1403715287912143104
1403715287962142976
1403715288012143104
1403715288062142976
1403715288112143104
1403715288162142976
1403715288212143104
1403715288262142976
1403715288312143104
1403715288362142976
1403715288412143104
1403715288462142976
1403715288512143104
1403715288562142976
1403715288612143104
1403715288662142976
1403715288712143104
1403715288762142976
1403715288812143104
1403715288862142976
1403715288912143104
1403715288962142976
1403715289012143104
1403715289062142976
1403715289112143104
1403715289162142976
1403715289212143104
1403715289262142976
1403715289312143104
1403715289362142976
1403715289412143104
1403715289462142976
1403715289512143104
1403715289562142976
1403715289612143104
1403715289662142976
1403715289712143104
1403715289762142976
1403715289812143104
1403715289862142976
1403715289912143104
1403715289962142976
1403715290012143104
1403715290062142976
1403715290112143104
1403715290162142976
1403715290212143104
1403715290262142976
1403715290312143104
1403715290362142976
1403715290412143104
1403715290462142976
1403715290512143104
1403715290562142976
1403715290612143104
1403715290662142976
1403715290712143104
1403715290762142976
1403715290812143104
1403715290862142976
1403715290912143104
1403715290962142976
1403715291012143104
1403715291062142976
1403715291112143104
1403715291162142976
1403715291212143104
1403715291262142976
1403715291312143104
1403715291362142976
1403715291412143104
1403715291462142976
1403715291512143104
1403715291562142976
1403715291612143104
1403715291662142976
1403715291712143104
1403715291762142976
1403715291812143104
1403715291862142976
1403715291912143104
1403715291962142976
1403715292012143104
1403715292062142976
1403715292112143104
1403715292162142976
1403715292212143104
1403715292262142976
1403715292312143104
1403715292362142976
1403715292412143104
1403715292462142976
1403715292512143104
1403715292562142976
1403715292612143104
1403715292662142976
1403715292712143104
1403715292762142976
1403715292812143104
1403715292862142976
1403715292912143104
1403715292962142976
1403715293012143104
1403715293062142976
1403715293112143104
1403715293162142976
1403715293212143104
1403715293262142976
1403715293312143104
1403715293362142976
1403715293412143104
1403715293462142976
1403715293512143104
1403715293562142976
1403715293612143104
1403715293662142976
1403715293712143104
1403715293762142976
1403715293812143104
1403715293862142976
1403715293912143104
1403715293962142976
1403715294012143104
1403715294062142976
1403715294112143104
1403715294162142976
1403715294212143104
1403715294262142976
1403715294312143104
1403715294362142976
1403715294412143104
1403715294462142976
1403715294512143104
1403715294562142976
1403715294612143104
1403715294662142976
1403715294712143104
1403715294762142976
1403715294812143104
1403715294862142976
1403715294912143104
1403715294962142976
1403715295012143104
1403715295062142976
1403715295112143104
1403715295162142976
1403715295212143104
1403715295262142976
1403715295312143104
1403715295362142976
1403715295412143104
1403715295462142976
1403715295512143104
1403715295562142976
1403715295612143104
1403715295662142976
1403715295712143104
1403715295762142976
1403715295812143104
1403715295862142976
1403715295912143104
1403715295962142976
1403715296012143104
1403715296062142976
1403715296112143104
1403715296162142976
1403715296212143104
1403715296262142976
1403715296312143104
1403715296362142976
1403715296412143104
1403715296462142976
1403715296512143104
1403715296562142976
1403715296612143104
1403715296662142976
1403715296712143104
1403715296762142976
1403715296812143104
1403715296862142976
1403715296912143104
1403715296962142976
1403715297012143104
1403715297062142976
1403715297112143104
1403715297162142976
1403715297212143104
1403715297262142976
1403715297312143104
1403715297362142976
1403715297412143104
1403715297462142976
1403715297512143104
1403715297562142976
1403715297612143104
1403715297662142976
1403715297712143104
1403715297762142976
1403715297812143104
1403715297862142976
1403715297912143104
1403715297962142976
1403715298012143104
1403715298062142976
1403715298112143104
1403715298162142976
1403715298212143104
1403715298262142976
1403715298312143104
1403715298362142976
1403715298412143104
1403715298462142976
1403715298512143104
1403715298562142976
1403715298612143104
1403715298662142976
1403715298712143104
1403715298762142976
1403715298812143104
1403715298862142976
1403715298912143104
1403715298962142976
1403715299012143104
1403715299062142976
1403715299112143104
1403715299162142976
1403715299212143104
1403715299262142976
1403715299312143104
1403715299362142976
1403715299412143104
1403715299462142976
1403715299512143104
1403715299562142976
1403715299612143104
1403715299662142976
1403715299712143104
1403715299762142976
1403715299812143104
1403715299862142976
1403715299912143104
1403715299962142976
1403715300012143104
1403715300062142976
1403715300112143104
1403715300162142976
1403715300212143104
1403715300262142976
1403715300312143104
1403715300362142976
1403715300412143104
1403715300462142976
1403715300512143104
1403715300562142976
1403715300612143104
1403715300662142976
1403715300712143104
1403715300762142976
1403715300812143104
1403715300862142976
1403715300912143104
1403715300962142976
1403715301012143104
1403715301062142976
1403715301112143104
1403715301162142976
1403715301212143104
1403715301262142976
1403715301312143104
1403715301362142976
1403715301412143104
1403715301462142976
1403715301512143104
1403715301562142976
1403715301612143104
1403715301662142976
1403715301712143104
1403715301762142976
1403715301812143104
1403715301862142976
1403715301912143104
1403715301962142976
1403715302012143104
1403715302062142976
1403715302112143104
1403715302162142976
1403715302212143104
1403715302262142976
1403715302312143104
1403715302362142976
1403715302412143104
1403715302462142976
1403715302512143104
1403715302562142976
1403715302612143104
1403715302662142976
1403715302712143104
1403715302762142976
1403715302812143104
1403715302862142976
1403715302912143104
1403715302962142976
1403715303012143104
1403715303062142976
1403715303112143104
1403715303162142976
1403715303212143104
1403715303262142976
1403715303312143104
1403715303362142976
1403715303412143104
1403715303462142976
1403715303512143104
1403715303562142976
1403715303612143104
1403715303662142976
1403715303712143104
1403715303762142976
1403715303812143104
1403715303862142976
1403715303912143104
1403715303962142976
1403715304012143104
1403715304062142976
1403715304112143104
1403715304162142976
1403715304212143104
1403715304262142976
1403715304312143104
1403715304362142976
1403715304412143104
1403715304462142976
1403715304512143104
1403715304562142976
1403715304612143104
1403715304662142976
1403715304712143104
1403715304762142976
1403715304812143104
1403715304862142976
1403715304912143104
1403715304962142976
1403715305012143104
1403715305062142976
1403715305112143104
1403715305162142976
1403715305212143104
1403715305262142976
1403715305312143104
1403715305362142976
1403715305412143104
1403715305462142976
1403715305512143104
1403715305562142976
1403715305612143104
1403715305662142976
1403715305712143104
1403715305762142976
1403715305812143104
1403715305862142976
1403715305912143104
1403715305962142976
1403715306012143104
1403715306062142976
1403715306112143104
1403715306162142976
1403715306212143104
1403715306262142976
1403715306312143104
1403715306362142976
1403715306412143104
1403715306462142976
1403715306512143104
1403715306562142976
1403715306612143104
1403715306662142976
1403715306712143104
1403715306762142976
1403715306812143104
1403715306862142976
1403715306912143104
1403715306962142976
1403715307012143104
1403715307062142976
1403715307112143104
1403715307162142976
1403715307212143104
1403715307262142976
1403715307312143104
1403715307362142976
1403715307412143104
1403715307462142976
1403715307512143104
1403715307562142976
1403715307612143104
1403715307662142976
1403715307712143104
1403715307762142976
1403715307812143104
1403715307862142976
1403715307912143104
1403715307962142976
1403715308012143104
1403715308062142976
1403715308112143104
1403715308162142976
1403715308212143104
1403715308262142976
1403715308312143104
1403715308362142976
1403715308412143104
1403715308462142976
1403715308512143104
1403715308562142976
1403715308612143104
1403715308662142976
1403715308712143104
1403715308762142976
1403715308812143104
1403715308862142976
1403715308912143104
1403715308962142976
1403715309012143104
1403715309062142976
1403715309112143104
1403715309162142976
1403715309212143104
1403715309262142976
1403715309312143104
1403715309362142976
1403715309412143104
1403715309462142976
1403715309512143104
1403715309562142976
1403715309612143104
1403715309662142976
1403715309712143104
1403715309762142976
1403715309812143104
1403715309862142976
1403715309912143104
1403715309962142976
1403715310012143104
1403715310062142976
1403715310112143104
1403715310162142976
1403715310212143104
1403715310262142976
1403715310312143104
1403715310362142976
1403715310412143104
1403715310462142976
1403715310512143104
1403715310562142976
1403715310612143104
1403715310662142976
1403715310712143104
1403715310762142976
1403715310812143104
1403715310862142976
1403715310912143104
1403715310962142976
1403715311012143104
1403715311062142976
1403715311112143104
1403715311162142976
1403715311212143104
1403715311262142976
1403715311312143104
1403715311362142976
1403715311412143104
1403715311462142976
1403715311512143104
1403715311562142976
1403715311612143104
1403715311662142976
1403715311712143104
1403715311762142976
1403715311812143104
1403715311862142976
1403715311912143104
1403715311962142976
1403715312012143104
1403715312062142976
1403715312112143104
1403715312162142976
1403715312212143104
1403715312262142976
1403715312312143104
1403715312362142976
1403715312412143104
1403715312462142976
1403715312512143104
1403715312562142976
1403715312612143104
1403715312662142976
1403715312712143104
1403715312762142976
1403715312812143104
1403715312862142976
1403715312912143104
1403715312962142976
1403715313012143104
1403715313062142976
1403715313112143104
1403715313162142976
1403715313212143104
1403715313262142976
1403715313312143104
1403715313362142976
1403715313412143104
1403715313462142976
1403715313512143104
1403715313562142976
1403715313612143104
1403715313662142976
1403715313712143104
1403715313762142976
1403715313812143104
1403715313862142976
1403715313912143104
1403715313962142976
1403715314012143104
1403715314062142976
1403715314112143104
1403715314162142976
1403715314212143104
1403715314262142976
1403715314312143104
1403715314362142976
1403715314412143104
1403715314462142976
1403715314512143104
1403715314562142976
1403715314612143104
1403715314662142976
1403715314712143104
1403715314762142976
1403715314812143104
1403715314862142976
1403715314912143104
1403715314962142976
1403715315012143104
1403715315062142976
1403715315112143104
1403715315162142976
1403715315212143104
1403715315262142976
1403715315312143104
1403715315362142976
1403715315412143104
1403715315462142976
1403715315512143104
1403715315562142976
1403715315612143104
1403715315662142976
1403715315712143104
1403715315762142976
1403715315812143104
1403715315862142976
1403715315912143104
1403715315962142976
1403715316012143104
1403715316062142976
1403715316112143104
1403715316162142976
1403715316212143104
1403715316262142976
1403715316312143104
1403715316362142976
1403715316412143104
1403715316462142976
1403715316512143104
1403715316562142976
1403715316612143104
1403715316662142976
1403715316712143104
1403715316762142976
1403715316812143104
1403715316862142976
1403715316912143104
1403715316962142976
1403715317012143104
1403715317062142976
1403715317112143104
1403715317162142976
1403715317212143104
1403715317262142976
1403715317312143104
1403715317362142976
1403715317412143104
1403715317462142976
1403715317512143104
1403715317562142976
1403715317612143104
1403715317662142976
1403715317712143104
1403715317762142976
1403715317812143104
1403715317862142976
1403715317912143104
1403715317962142976
1403715318012143104
1403715318062142976
1403715318112143104
1403715318162142976
1403715318212143104
1403715318262142976
1403715318312143104
1403715318362142976
1403715318412143104
1403715318462142976
1403715318512143104
1403715318562142976
1403715318612143104
1403715318662142976
1403715318712143104
1403715318762142976
1403715318812143104
1403715318862142976
1403715318912143104
1403715318962142976
1403715319012143104
1403715319062142976
1403715319112143104
1403715319162142976
1403715319212143104
1403715319262142976
1403715319312143104
1403715319362142976
1403715319412143104
1403715319462142976
1403715319512143104
1403715319562142976
1403715319612143104
1403715319662142976
1403715319712143104
1403715319762142976
1403715319812143104
1403715319862142976
1403715319912143104
1403715319962142976
1403715320012143104
1403715320062142976
1403715320112143104
1403715320162142976
1403715320212143104
1403715320262142976
1403715320312143104
1403715320362142976
1403715320412143104
1403715320462142976
1403715320512143104
1403715320562142976
1403715320612143104
1403715320662142976
1403715320712143104
1403715320762142976
1403715320812143104
1403715320862142976
1403715320912143104
1403715320962142976
1403715321012143104
1403715321062142976
1403715321112143104
1403715321162142976
1403715321212143104
1403715321262142976
1403715321312143104
1403715321362142976
1403715321412143104
1403715321462142976
1403715321512143104
1403715321562142976
1403715321612143104
1403715321662142976
1403715321712143104
1403715321762142976
1403715321812143104
1403715321862142976
1403715321912143104
1403715321962142976
1403715322012143104
1403715322062142976
1403715322112143104
1403715322162142976
1403715322212143104
1403715322262142976
1403715322312143104
1403715322362142976
1403715322412143104
1403715322462142976
1403715322512143104
1403715322562142976
1403715322612143104
1403715322662142976
1403715322712143104
1403715322762142976
1403715322812143104
1403715322862142976
1403715322912143104
1403715322962142976
1403715323012143104
1403715323062142976
1403715323112143104
1403715323162142976
1403715323212143104
1403715323262142976
1403715323312143104
1403715323362142976
1403715323412143104
1403715323462142976
1403715323512143104
1403715323562142976
1403715323612143104
1403715323662142976
1403715323712143104
1403715323762142976
1403715323812143104
1403715323862142976
1403715323912143104
1403715323962142976
1403715324012143104
1403715324062142976
1403715324112143104
1403715324162142976
1403715324212143104
1403715324262142976
1403715324312143104
1403715324362142976
1403715324412143104
1403715324462142976
1403715324512143104
1403715324562142976
1403715324612143104
1403715324662142976
1403715324712143104
1403715324762142976
1403715324812143104
1403715324862142976
1403715324912143104
1403715324962142976
1403715325012143104
1403715325062142976
1403715325112143104
1403715325162142976
1403715325212143104
1403715325262142976
1403715325312143104
1403715325362142976
1403715325412143104
1403715325462142976
1403715325512143104
1403715325562142976
1403715325612143104
1403715325662142976
1403715325712143104
1403715325762142976
1403715325812143104
1403715325862142976
1403715325912143104
1403715325962142976
1403715326012143104
1403715326062142976
1403715326112143104
1403715326162142976
1403715326212143104
1403715326262142976
1403715326312143104
1403715326362142976
1403715326412143104
1403715326462142976
1403715326512143104
1403715326562142976
1403715326612143104
1403715326662142976
1403715326712143104
1403715326762142976
1403715326812143104
1403715326862142976
1403715326912143104
1403715326962142976
1403715327012143104
1403715327062142976
1403715327112143104
1403715327162142976
1403715327212143104
1403715327262142976
1403715327312143104
1403715327362142976
1403715327412143104
1403715327462142976
1403715327512143104
1403715327562142976
1403715327612143104
1403715327662142976
1403715327712143104
1403715327762142976
1403715327812143104
1403715327862142976
1403715327912143104
1403715327962142976
1403715328012143104
1403715328062142976
1403715328112143104
1403715328162142976
1403715328212143104
1403715328262142976
1403715328312143104
1403715328362142976
1403715328412143104
1403715328462142976
1403715328512143104
1403715328562142976
1403715328612143104
1403715328662142976
1403715328712143104
1403715328762142976
1403715328812143104
1403715328862142976
1403715328912143104
1403715328962142976
1403715329012143104
1403715329062142976
1403715329112143104
1403715329162142976
1403715329212143104
1403715329262142976
1403715329312143104
1403715329362142976
1403715329412143104
1403715329462142976
1403715329512143104
1403715329562142976
1403715329612143104
1403715329662142976
1403715329712143104
1403715329762142976
1403715329812143104
1403715329862142976
1403715329912143104
1403715329962142976
1403715330012143104
1403715330062142976
1403715330112143104
1403715330162142976
1403715330212143104
1403715330262142976
1403715330312143104
1403715330362142976
1403715330412143104
1403715330462142976
1403715330512143104
1403715330562142976
1403715330612143104
1403715330662142976
1403715330712143104
1403715330762142976
1403715330812143104
1403715330862142976
1403715330912143104
1403715330962142976
1403715331012143104
1403715331062142976
1403715331112143104
1403715331162142976
1403715331212143104
1403715331262142976
1403715331312143104
1403715331362142976
1403715331412143104
1403715331462142976
1403715331512143104
1403715331562142976
1403715331612143104
1403715331662142976
1403715331712143104
1403715331762142976
1403715331812143104
1403715331862142976
1403715331912143104
1403715331962142976
1403715332012143104
1403715332062142976
1403715332112143104
1403715332162142976
1403715332212143104
1403715332262142976
1403715332312143104
1403715332362142976
1403715332412143104
1403715332462142976
1403715332512143104
1403715332562142976
1403715332612143104
1403715332662142976
1403715332712143104
1403715332762142976
1403715332812143104
1403715332862142976
1403715332912143104
1403715332962142976
1403715333012143104
1403715333062142976
1403715333112143104
1403715333162142976
1403715333212143104
1403715333262142976
1403715333312143104
1403715333362142976
1403715333412143104
1403715333462142976
1403715333512143104
1403715333562142976
1403715333612143104
1403715333662142976
1403715333712143104
1403715333762142976
1403715333812143104
1403715333862142976
1403715333912143104
1403715333962142976
1403715334012143104
1403715334062142976
1403715334112143104
1403715334162142976
1403715334212143104
1403715334262142976
1403715334312143104
1403715334362142976
1403715334412143104
1403715334462142976
1403715334512143104
1403715334562142976
1403715334612143104
1403715334662142976
1403715334712143104
1403715334762142976
1403715334812143104
1403715334862142976
1403715334912143104
1403715334962142976
1403715335012143104
1403715335062142976
1403715335112143104
1403715335162142976
1403715335212143104
1403715335262142976
1403715335312143104
1403715335362142976
1403715335412143104
1403715335462142976
1403715335512143104
1403715335562142976
1403715335612143104
1403715335662142976
1403715335712143104
1403715335762142976
1403715335812143104
1403715335862142976
1403715335912143104
1403715335962142976
1403715336012143104
1403715336062142976
1403715336112143104
1403715336162142976
1403715336212143104
1403715336262142976
1403715336312143104
1403715336362142976
1403715336412143104
1403715336462142976
1403715336512143104
1403715336562142976
1403715336612143104
1403715336662142976
1403715336712143104
1403715336762142976
1403715336812143104
1403715336862142976
1403715336912143104
1403715336962142976
1403715337012143104
1403715337062142976
1403715337112143104
1403715337162142976
1403715337212143104
1403715337262142976
1403715337312143104
1403715337362142976
1403715337412143104
1403715337462142976
1403715337512143104
1403715337562142976
1403715337612143104
1403715337662142976
1403715337712143104
1403715337762142976
1403715337812143104
1403715337862142976
1403715337912143104
1403715337962142976
1403715338012143104
1403715338062142976
1403715338112143104
1403715338162142976
1403715338212143104
1403715338262142976
1403715338312143104
1403715338362142976
1403715338412143104
1403715338462142976
1403715338512143104
1403715338562142976
1403715338612143104
1403715338662142976
1403715338712143104
1403715338762142976
1403715338812143104
1403715338862142976
1403715338912143104
1403715338962142976
1403715339012143104
1403715339062142976
1403715339112143104
1403715339162142976
1403715339212143104
1403715339262142976
1403715339312143104
1403715339362142976
1403715339412143104
1403715339462142976
1403715339512143104
1403715339562142976
1403715339612143104
1403715339662142976
1403715339712143104
1403715339762142976
1403715339812143104
1403715339862142976
1403715339912143104
1403715339962142976
1403715340012143104
1403715340062142976
1403715340112143104
1403715340162142976
1403715340212143104
1403715340262142976
1403715340312143104
1403715340362142976
1403715340412143104
1403715340462142976
1403715340512143104
1403715340562142976
1403715340612143104
1403715340662142976
1403715340712143104
1403715340762142976
1403715340812143104
1403715340862142976
1403715340912143104
1403715340962142976
1403715341012143104
1403715341062142976
1403715341112143104
1403715341162142976
1403715341212143104
1403715341262142976
1403715341312143104
1403715341362142976
1403715341412143104
1403715341462142976
1403715341512143104
1403715341562142976
1403715341612143104
1403715341662142976
1403715341712143104
1403715341762142976
1403715341812143104
1403715341862142976
1403715341912143104
1403715341962142976
1403715342012143104
1403715342062142976
1403715342112143104
1403715342162142976
1403715342212143104
1403715342262142976
1403715342312143104
1403715342362142976
1403715342412143104
1403715342462142976
1403715342512143104
1403715342562142976
1403715342612143104
1403715342662142976
1403715342712143104
1403715342762142976
1403715342812143104
1403715342862142976
1403715342912143104
1403715342962142976
1403715343012143104
1403715343062142976
1403715343112143104
1403715343162142976
1403715343212143104
1403715343262142976
1403715343312143104
1403715343362142976
1403715343412143104
1403715343462142976
1403715343512143104
1403715343562142976
1403715343612143104
1403715343662142976
1403715343712143104
1403715343762142976
1403715343812143104
1403715343862142976
1403715343912143104
1403715343962142976
1403715344012143104
1403715344062142976
1403715344112143104
1403715344162142976
1403715344212143104
1403715344262142976
1403715344312143104
1403715344362142976
1403715344412143104
1403715344462142976
1403715344512143104
1403715344562142976
1403715344612143104
1403715344662142976
1403715344712143104
1403715344762142976
1403715344812143104
1403715344862142976
1403715344912143104
1403715344962142976
1403715345012143104
1403715345062142976
1403715345112143104
1403715345162142976
1403715345212143104
1403715345262142976
1403715345312143104
1403715345362142976
1403715345412143104
1403715345462142976
1403715345512143104
1403715345562142976
1403715345612143104
1403715345662142976
1403715345712143104
1403715345762142976
1403715345812143104
1403715345862142976
1403715345912143104
1403715345962142976
1403715346012143104
1403715346062142976
1403715346112143104
1403715346162142976
1403715346212143104
1403715346262142976
1403715346312143104
1403715346362142976
1403715346412143104
1403715346462142976
1403715346512143104
1403715346562142976
1403715346612143104
1403715346662142976
1403715346712143104
1403715346762142976
1403715346812143104
1403715346862142976
1403715346912143104
1403715346962142976
1403715347012143104
1403715347062142976
1403715347112143104
1403715347162142976
1403715347212143104
1403715347262142976
1403715347312143104
1403715347362142976
1403715347412143104
1403715347462142976
1403715347512143104
1403715347562142976
1403715347612143104
1403715347662142976
1403715347712143104
1403715347762142976
1403715347812143104
1403715347862142976
1403715347912143104
1403715347962142976
1403715348012143104
1403715348062142976
1403715348112143104
1403715348162142976
1403715348212143104
1403715348262142976
1403715348312143104
1403715348362142976
1403715348412143104
1403715348462142976
1403715348512143104
1403715348562142976
1403715348612143104
1403715348662142976
1403715348712143104
1403715348762142976
1403715348812143104
1403715348862142976
1403715348912143104
1403715348962142976
1403715349012143104
1403715349062142976
1403715349112143104
1403715349162142976
1403715349212143104
1403715349262142976
1403715349312143104
1403715349362142976
1403715349412143104
1403715349462142976
1403715349512143104
1403715349562142976
1403715349612143104
1403715349662142976
1403715349712143104
1403715349762142976
1403715349812143104
1403715349862142976
1403715349912143104
1403715349962142976
1403715350012143104
1403715350062142976
1403715350112143104
1403715350162142976
1403715350212143104
1403715350262142976
1403715350312143104
1403715350362142976
1403715350412143104
1403715350462142976
1403715350512143104
1403715350562142976
1403715350612143104
1403715350662142976
1403715350712143104
1403715350762142976
1403715350812143104
1403715350862142976
1403715350912143104
1403715350962142976
1403715351012143104
1403715351062142976
1403715351112143104
1403715351162142976
1403715351212143104
1403715351262142976
1403715351312143104
1403715351362142976
1403715351412143104
1403715351462142976
1403715351512143104
1403715351562142976
1403715351612143104
1403715351662142976
1403715351712143104
1403715351762142976
1403715351812143104
1403715351862142976
1403715351912143104
1403715351962142976
1403715352012143104
1403715352062142976
1403715352112143104
1403715352162142976
1403715352212143104
1403715352262142976
1403715352312143104
1403715352362142976
1403715352412143104
1403715352462142976
1403715352512143104
1403715352562142976
1403715352612143104
1403715352662142976
1403715352712143104
1403715352762142976
1403715352812143104
1403715352862142976
1403715352912143104
1403715352962142976
1403715353012143104
1403715353062142976
1403715353112143104
1403715353162142976
1403715353212143104
1403715353262142976
1403715353312143104
1403715353362142976
1403715353412143104
1403715353462142976
1403715353512143104
1403715353562142976
1403715353612143104
1403715353662142976
1403715353712143104
1403715353762142976
1403715353812143104
1403715353862142976
1403715353912143104
1403715353962142976
1403715354012143104
1403715354062142976
1403715354112143104
1403715354162142976
1403715354212143104
1403715354262142976
1403715354312143104
1403715354362142976
1403715354412143104
1403715354462142976
1403715354512143104
1403715354562142976
1403715354612143104
1403715354662142976
1403715354712143104
1403715354762142976
1403715354812143104
1403715354862142976
1403715354912143104
1403715354962142976
1403715355012143104
1403715355062142976
1403715355112143104
1403715355162142976
1403715355212143104
1403715355262142976
1403715355312143104
1403715355362142976
1403715355412143104
1403715355462142976
1403715355512143104
1403715355562142976
1403715355612143104
1403715355662142976
1403715355712143104
1403715355762142976
1403715355812143104
1403715355862142976
1403715355912143104
1403715355962142976
1403715356012143104
1403715356062142976
1403715356112143104
1403715356162142976
1403715356212143104
1403715356262142976
1403715356312143104
1403715356362142976
1403715356412143104
1403715356462142976
1403715356512143104
1403715356562142976
1403715356612143104
1403715356662142976
1403715356712143104
1403715356762142976
1403715356812143104
1403715356862142976
1403715356912143104
1403715356962142976
1403715357012143104
1403715357062142976
1403715357112143104
1403715357162142976
1403715357212143104
1403715357262142976
1403715357312143104
1403715357362142976
1403715357412143104
1403715357462142976
1403715357512143104
1403715357562142976
1403715357612143104
1403715357662142976
1403715357712143104
1403715357762142976
1403715357812143104
1403715357862142976
1403715357912143104
1403715357962142976
1403715358012143104
1403715358062142976
1403715358112143104
1403715358162142976
1403715358212143104
1403715358262142976
1403715358312143104
1403715358362142976
1403715358412143104
1403715358462142976
1403715358512143104
1403715358562142976
1403715358612143104
1403715358662142976
1403715358712143104
1403715358762142976
1403715358812143104
1403715358862142976
1403715358912143104
1403715358962142976
1403715359012143104
1403715359062142976
1403715359112143104
1403715359162142976
1403715359212143104
1403715359262142976
1403715359312143104
1403715359362142976
1403715359412143104
1403715359462142976
1403715359512143104
1403715359562142976
1403715359612143104
1403715359662142976
1403715359712143104
1403715359762142976
1403715359812143104
1403715359862142976
1403715359912143104
1403715359962142976
1403715360012143104
1403715360062142976
1403715360112143104
1403715360162142976
1403715360212143104
1403715360262142976
1403715360312143104
1403715360362142976
1403715360412143104
1403715360462142976
1403715360512143104
1403715360562142976
1403715360612143104
1403715360662142976
1403715360712143104
1403715360762142976
1403715360812143104
1403715360862142976
1403715360912143104
1403715360962142976
1403715361012143104
1403715361062142976
1403715361112143104
1403715361162142976
1403715361212143104
1403715361262142976
1403715361312143104
1403715361362142976
1403715361412143104
1403715361462142976
1403715361512143104
1403715361562142976
1403715361612143104
1403715361662142976
1403715361712143104
1403715361762142976
1403715361812143104
1403715361862142976
1403715361912143104
1403715361962142976
1403715362012143104
1403715362062142976
1403715362112143104
1403715362162142976
1403715362212143104
1403715362262142976
1403715362312143104
1403715362362142976
1403715362412143104
1403715362462142976
1403715362512143104
1403715362562142976
1403715362612143104
1403715362662142976
1403715362712143104
1403715362762142976
1403715362812143104
1403715362862142976
1403715362912143104
1403715362962142976
1403715363012143104
1403715363062142976
1403715363112143104
1403715363162142976
1403715363212143104
1403715363262142976
1403715363312143104
1403715363362142976
1403715363412143104
1403715363462142976
1403715363512143104
1403715363562142976
1403715363612143104
1403715363662142976
1403715363712143104
1403715363762142976
1403715363812143104
1403715363862142976
1403715363912143104
1403715363962142976
1403715364012143104
1403715364062142976
1403715364112143104
1403715364162142976
1403715364212143104
1403715364262142976
1403715364312143104
1403715364362142976
1403715364412143104
1403715364462142976
1403715364512143104
1403715364562142976
1403715364612143104
1403715364662142976
1403715364712143104
1403715364762142976
1403715364812143104
1403715364862142976
1403715364912143104
1403715364962142976
1403715365012143104
1403715365062142976
1403715365112143104
1403715365162142976
1403715365212143104
1403715365262142976
1403715365312143104
1403715365362142976
1403715365412143104
1403715365462142976
1403715365512143104
1403715365562142976
1403715365612143104
1403715365662142976
1403715365712143104
1403715365762142976
1403715365812143104
1403715365862142976
1403715365912143104
1403715365962142976
1403715366012143104
1403715366062142976
1403715366112143104
1403715366162142976
1403715366212143104
1403715366262142976
1403715366312143104
1403715366362142976
1403715366412143104
1403715366462142976
1403715366512143104
1403715366562142976
1403715366612143104
1403715366662142976
1403715366712143104
1403715366762142976
1403715366812143104
1403715366862142976
1403715366912143104
1403715366962142976
1403715367012143104
1403715367062142976
1403715367112143104
1403715367162142976
1403715367212143104
1403715367262142976
1403715367312143104
1403715367362142976
1403715367412143104
1403715367462142976
1403715367512143104
1403715367562142976
1403715367612143104
1403715367662142976
1403715367712143104
1403715367762142976
1403715367812143104
1403715367862142976
1403715367912143104
1403715367962142976
1403715368012143104
1403715368062142976
1403715368112143104
1403715368162142976
1403715368212143104
1403715368262142976
1403715368312143104
1403715368362142976
1403715368412143104
1403715368462142976
1403715368512143104
1403715368562142976
1403715368612143104
1403715368662142976
1403715368712143104
1403715368762142976
1403715368812143104
1403715368862142976
1403715368912143104
1403715368962142976
1403715369012143104
1403715369062142976
1403715369112143104
1403715369162142976
1403715369212143104
1403715369262142976
1403715369312143104
1403715369362142976
1403715369412143104
1403715369462142976
1403715369512143104
1403715369562142976
1403715369612143104
1403715369662142976
1403715369712143104
1403715369762142976
1403715369812143104
1403715369862142976
1403715369912143104
1403715369962142976
1403715370012143104
1403715370062142976
1403715370112143104
1403715370162142976
1403715370212143104
1403715370262142976
1403715370312143104
1403715370362142976
1403715370412143104
1403715370462142976
1403715370512143104
1403715370562142976
1403715370612143104
1403715370662142976
1403715370712143104
1403715370762142976
1403715370812143104
1403715370862142976
1403715370912143104
1403715370962142976
1403715371012143104
1403715371062142976
1403715371112143104
1403715371162142976
1403715371212143104
1403715371262142976
1403715371312143104
1403715371362142976
1403715371412143104
1403715371462142976
1403715371512143104
1403715371562142976
1403715371612143104
1403715371662142976
1403715371712143104
1403715371762142976
1403715371812143104
1403715371862142976
1403715371912143104
1403715371962142976
1403715372012143104
1403715372062142976
1403715372112143104
1403715372162142976
1403715372212143104
1403715372262142976
1403715372312143104
1403715372362142976
1403715372412143104
1403715372462142976
1403715372512143104
1403715372562142976
1403715372612143104
1403715372662142976
1403715372712143104
1403715372762142976
1403715372812143104
1403715372862142976
1403715372912143104
1403715372962142976
1403715373012143104
1403715373062142976
1403715373112143104
1403715373162142976
1403715373212143104
1403715373262142976
1403715373312143104
1403715373362142976
1403715373412143104
1403715373462142976
1403715373512143104
1403715373562142976
1403715373612143104
1403715373662142976
1403715373712143104
1403715373762142976
1403715373812143104
1403715373862142976
1403715373912143104
1403715373962142976
1403715374012143104
1403715374062142976
1403715374112143104
1403715374162142976
1403715374212143104
1403715374262142976
1403715374312143104
1403715374362142976
1403715374412143104
1403715374462142976
1403715374512143104
1403715374562142976
1403715374612143104
1403715374662142976
1403715374712143104
1403715374762142976
1403715374812143104
1403715374862142976
1403715374912143104
1403715374962142976
1403715375012143104
1403715375062142976
1403715375112143104
1403715375162142976
1403715375212143104
1403715375262142976
1403715375312143104
1403715375362142976
1403715375412143104
1403715375462142976
1403715375512143104
1403715375562142976
1403715375612143104
1403715375662142976
1403715375712143104
1403715375762142976
1403715375812143104
1403715375862142976
1403715375912143104
1403715375962142976
1403715376012143104
1403715376062142976
1403715376112143104
1403715376162142976
1403715376212143104
1403715376262142976
1403715376312143104
1403715376362142976
1403715376412143104
1403715376462142976
1403715376512143104
1403715376562142976
1403715376612143104
1403715376662142976
1403715376712143104
1403715376762142976
1403715376812143104
1403715376862142976
1403715376912143104
1403715376962142976
1403715377012143104
1403715377062142976
1403715377112143104
1403715377162142976
1403715377212143104
1403715377262142976
1403715377312143104
1403715377362142976
1403715377412143104
1403715377462142976
1403715377512143104
1403715377562142976
1403715377612143104
1403715377662142976
1403715377712143104
1403715377762142976
1403715377812143104
1403715377862142976
1403715377912143104
1403715377962142976
1403715378012143104
1403715378062142976
1403715378112143104
1403715378162142976
1403715378212143104
1403715378262142976
1403715378312143104
1403715378362142976
1403715378412143104
1403715378462142976
1403715378512143104
1403715378562142976
1403715378612143104
1403715378662142976
1403715378712143104
1403715378762142976
1403715378812143104
1403715378862142976
1403715378912143104
1403715378962142976
1403715379012143104
1403715379062142976
1403715379112143104
1403715379162142976
1403715379212143104
1403715379262142976
1403715379312143104
1403715379362142976
1403715379412143104
1403715379462142976
1403715379512143104
1403715379562142976
1403715379612143104
1403715379662142976
1403715379712143104
1403715379762142976
1403715379812143104
1403715379862142976
1403715379912143104
1403715379962142976
1403715380012143104
1403715380062142976
1403715380112143104
1403715380162142976
1403715380212143104
1403715380262142976
1403715380312143104
1403715380362142976
1403715380412143104
1403715380462142976
1403715380512143104
1403715380562142976
1403715380612143104
1403715380662142976
1403715380712143104
1403715380762142976
1403715380812143104
1403715380862142976
1403715380912143104
1403715380962142976
1403715381012143104
1403715381062142976
1403715381112143104
1403715381162142976
1403715381212143104
1403715381262142976
1403715381312143104
1403715381362142976
1403715381412143104
1403715381462142976
1403715381512143104
1403715381562142976
1403715381612143104
1403715381662142976
1403715381712143104
1403715381762142976
1403715381812143104
1403715381862142976
1403715381912143104
1403715381962142976
1403715382012143104
1403715382062142976
1403715382112143104
1403715382162142976
1403715382212143104
1403715382262142976
1403715382312143104
1403715382362142976
1403715382412143104
1403715382462142976
1403715382512143104
1403715382562142976
1403715382612143104
1403715382662142976
1403715382712143104
1403715382762142976
1403715382812143104
1403715382862142976
1403715382912143104
1403715382962142976
1403715383012143104
1403715383062142976
1403715383112143104
1403715383162142976
1403715383212143104
1403715383262142976
1403715383312143104
1403715383362142976
1403715383412143104
1403715383462142976
1403715383512143104
1403715383562142976
1403715383612143104
1403715383662142976
1403715383712143104
1403715383762142976
1403715383812143104
1403715383862142976
1403715383912143104
1403715383962142976
1403715384012143104
1403715384062142976
1403715384112143104
1403715384162142976
1403715384212143104
1403715384262142976
1403715384312143104
1403715384362142976
1403715384412143104
1403715384462142976
1403715384512143104
1403715384562142976
1403715384612143104
1403715384662142976
1403715384712143104
1403715384762142976
1403715384812143104
1403715384862142976
1403715384912143104
1403715384962142976
1403715385012143104
1403715385062142976
1403715385112143104
1403715385162142976
1403715385212143104
1403715385262142976
1403715385312143104
1403715385362142976
1403715385412143104
1403715385462142976
1403715385512143104
1403715385562142976
1403715385612143104
1403715385662142976
1403715385712143104
1403715385762142976
1403715385812143104
1403715385862142976
1403715385912143104
1403715385962142976
1403715386012143104
1403715386062142976
1403715386112143104
1403715386162142976
1403715386212143104
1403715386262142976
1403715386312143104
1403715386362142976
1403715386412143104
1403715386462142976
1403715386512143104
1403715386562142976
1403715386612143104
1403715386662142976
1403715386712143104
1403715386762142976
1403715386812143104
1403715386862142976
1403715386912143104
1403715386962142976
1403715387012143104
1403715387062142976
1403715387112143104
1403715387162142976
1403715387212143104
1403715387262142976
1403715387312143104
1403715387362142976
1403715387412143104
1403715387462142976
1403715387512143104
1403715387562142976
1403715387612143104
1403715387662142976
1403715387712143104
1403715387762142976
1403715387812143104
1403715387862142976
1403715387912143104
1403715387962142976
1403715388012143104
1403715388062142976
1403715388112143104
1403715388162142976
1403715388212143104
1403715388262142976
1403715388312143104
1403715388362142976
1403715388412143104
1403715388462142976
1403715388512143104
1403715388562142976
1403715388612143104
1403715388662142976
1403715388712143104
1403715388762142976
1403715388812143104
1403715388862142976
1403715388912143104
1403715388962142976
1403715389012143104
1403715389062142976
1403715389112143104
1403715389162142976
1403715389212143104
1403715389262142976
1403715389312143104
1403715389362142976
1403715389412143104
1403715389462142976
1403715389512143104
1403715389562142976
1403715389612143104
1403715389662142976
1403715389712143104
1403715389762142976
1403715389812143104
1403715389862142976
1403715389912143104
1403715389962142976
1403715390012143104
1403715390062142976
1403715390112143104
1403715390162142976
1403715390212143104
1403715390262142976
1403715390312143104
1403715390362142976
1403715390412143104
1403715390462142976
1403715390512143104
1403715390562142976
1403715390612143104
1403715390662142976
1403715390712143104
1403715390762142976
1403715390812143104
1403715390862142976
1403715390912143104
1403715390962142976
1403715391012143104
1403715391062142976
1403715391112143104
1403715391162142976
1403715391212143104
1403715391262142976
1403715391312143104
1403715391362142976
1403715391412143104
1403715391462142976
1403715391512143104
1403715391562142976
1403715391612143104
1403715391662142976
1403715391712143104
1403715391762142976
1403715391812143104
1403715391862142976
1403715391912143104
1403715391962142976
1403715392012143104
1403715392062142976
1403715392112143104
1403715392162142976
1403715392212143104
1403715392262142976
1403715392312143104
1403715392362142976
1403715392412143104
1403715392462142976
1403715392512143104
1403715392562142976
1403715392612143104
1403715392662142976
1403715392712143104
1403715392762142976
1403715392812143104
1403715392862142976
1403715392912143104
1403715392962142976
1403715393012143104
1403715393062142976
1403715393112143104
1403715393162142976
1403715393212143104
1403715393262142976
1403715393312143104
1403715393362142976
1403715393412143104
1403715393462142976
1403715393512143104
1403715393562142976
1403715393612143104
1403715393662142976
1403715393712143104
1403715393762142976
1403715393812143104
1403715393862142976
1403715393912143104
1403715393962142976
1403715394012143104
1403715394062142976
1403715394112143104
1403715394162142976
1403715394212143104
1403715394262142976
1403715394312143104
1403715394362142976
1403715394412143104
1403715394462142976
1403715394512143104
1403715394562142976
1403715394612143104
1403715394662142976
1403715394712143104
1403715394762142976
1403715394812143104
1403715394862142976
1403715394912143104
1403715394962142976
1403715395012143104
1403715395062142976
1403715395112143104
1403715395162142976
1403715395212143104
1403715395262142976
1403715395312143104
1403715395362142976
1403715395412143104
1403715395462142976
1403715395512143104
1403715395562142976
1403715395612143104
1403715395662142976
1403715395712143104
1403715395762142976
1403715395812143104
1403715395862142976
1403715395912143104
1403715395962142976
1403715396012143104
1403715396062142976
1403715396112143104
1403715396162142976
1403715396212143104
1403715396262142976
1403715396312143104
1403715396362142976
1403715396412143104
1403715396462142976
1403715396512143104
1403715396562142976
1403715396612143104
1403715396662142976
1403715396712143104
1403715396762142976
1403715396812143104
1403715396862142976
1403715396912143104
1403715396962142976
1403715397012143104
1403715397062142976
1403715397112143104
1403715397162142976
1403715397212143104
1403715397262142976
1403715397312143104
1403715397362142976
1403715397412143104
1403715397462142976
1403715397512143104
1403715397562142976
1403715397612143104
1403715397662142976
1403715397712143104
1403715397762142976
1403715397812143104
1403715397862142976
1403715397912143104
1403715397962142976
1403715398012143104
1403715398062142976
1403715398112143104
1403715398162142976
1403715398212143104
1403715398262142976
1403715398312143104
1403715398362142976
1403715398412143104
1403715398462142976
1403715398512143104
1403715398562142976
1403715398612143104
1403715398662142976
1403715398712143104
1403715398762142976
1403715398812143104
1403715398862142976
1403715398912143104
1403715398962142976
1403715399012143104
1403715399062142976
1403715399112143104
1403715399162142976
1403715399212143104
1403715399262142976
1403715399312143104
1403715399362142976
1403715399412143104
1403715399462142976
1403715399512143104
1403715399562142976
1403715399612143104
1403715399662142976
1403715399712143104
1403715399762142976
1403715399812143104
1403715399862142976
1403715399912143104
1403715399962142976
1403715400012143104
1403715400062142976
1403715400112143104
1403715400162142976
1403715400212143104
1403715400262142976
1403715400312143104
1403715400362142976
1403715400412143104
1403715400462142976
1403715400512143104
1403715400562142976
1403715400612143104
1403715400662142976
1403715400712143104
1403715400762142976
1403715400812143104
1403715400862142976
1403715400912143104
1403715400962142976
1403715401012143104
1403715401062142976
1403715401112143104
1403715401162142976
1403715401212143104
1403715401262142976
1403715401312143104
1403715401362142976
1403715401412143104
1403715401462142976
1403715401512143104
1403715401562142976
1403715401612143104
1403715401662142976
1403715401712143104
1403715401762142976
1403715401812143104
1403715401862142976
1403715401912143104
1403715401962142976
1403715402012143104
1403715402062142976
1403715402112143104
1403715402162142976
1403715402212143104
1403715402262142976
1403715402312143104
1403715402362142976
1403715402412143104
1403715402462142976
1403715402512143104
1403715402562142976
1403715402612143104
1403715402662142976
1403715402712143104
1403715402762142976
1403715402812143104
1403715402862142976
1403715402912143104
1403715402962142976
1403715403012143104
1403715403062142976
1403715403112143104
1403715403162142976
1403715403212143104
1403715403262142976
1403715403312143104
1403715403362142976
1403715403412143104
1403715403462142976
1403715403512143104
1403715403562142976
1403715403612143104
1403715403662142976
1403715403712143104
1403715403762142976
1403715403812143104
1403715403862142976
1403715403912143104
1403715403962142976
1403715404012143104
1403715404062142976
1403715404112143104
1403715404162142976
1403715404212143104
1403715404262142976
1403715404312143104
1403715404362142976
1403715404412143104
1403715404462142976
1403715404512143104
1403715404562142976
1403715404612143104
1403715404662142976
1403715404712143104
1403715404762142976
1403715404812143104
1403715404862142976
1403715404912143104
1403715404962142976
1403715405012143104
1403715405062142976
1403715405112143104
1403715405162142976
1403715405212143104
1403715405262142976
1403715405312143104
1403715405362142976
1403715405412143104
1403715405462142976
1403715405512143104
1403715405562142976
1403715405612143104
1403715405662142976
1403715405712143104
1403715405762142976
1403715405812143104
1403715405862142976
1403715405912143104
1403715405962142976
1403715406012143104
1403715406062142976
1403715406112143104
1403715406162142976
1403715406212143104
1403715406262142976
1403715406312143104
1403715406362142976
1403715406412143104
1403715406462142976
1403715406512143104
1403715406562142976
1403715406612143104
1403715406662142976
1403715406712143104
1403715406762142976
1403715406812143104
1403715406862142976
1403715406912143104
1403715406962142976
1403715407012143104
1403715407062142976
1403715407112143104
1403715407162142976
1403715407212143104
1403715407262142976
1403715407312143104
1403715407362142976
1403715407412143104
1403715407462142976
1403715407512143104
1403715407562142976
1403715407612143104
1403715407662142976
1403715407712143104
1403715407762142976
1403715407812143104
1403715407862142976
1403715407912143104
1403715407962142976
1403715408012143104
1403715408062142976
1403715408112143104
1403715408162142976
1403715408212143104
1403715408262142976
1403715408312143104
1403715408362142976
1403715408412143104
1403715408462142976
1403715408512143104
1403715408562142976
1403715408612143104
1403715408662142976
1403715408712143104
1403715408762142976
1403715408812143104
1403715408862142976
1403715408912143104
1403715408962142976
1403715409012143104
1403715409062142976
1403715409112143104
1403715409162142976
1403715409212143104
1403715409262142976
1403715409312143104
1403715409362142976
1403715409412143104
1403715409462142976
1403715409512143104
1403715409562142976
1403715409612143104
1403715409662142976
1403715409712143104
1403715409762142976
1403715409812143104
1403715409862142976
1403715409912143104
1403715409962142976
1403715410012143104
1403715410062142976
1403715410112143104
1403715410162142976
1403715410212143104
1403715410262142976
1403715410312143104
1403715410362142976
1403715410412143104
1403715410462142976
1403715410512143104
1403715410562142976
1403715410612143104
1403715410662142976
1403715410712143104
1403715410762142976
1403715410812143104
1403715410862142976
1403715410912143104
1403715410962142976
1403715411012143104
1403715411062142976
1403715411112143104
1403715411162142976
1403715411212143104
1403715411262142976
1403715411312143104
1403715411362142976
1403715411412143104
1403715411462142976
1403715411512143104
1403715411562142976
1403715411612143104
1403715411662142976
1403715411712143104
1403715411762142976
1403715411812143104
1403715411862142976
1403715411912143104
1403715411962142976
1403715412012143104
1403715412062142976
1403715412112143104
1403715412162142976
1403715412212143104
1403715412262142976
1403715412312143104
1403715412362142976
1403715412412143104
1403715412462142976
1403715412512143104
1403715412562142976
1403715412612143104
1403715412662142976
1403715412712143104
1403715412762142976
1403715412812143104
1403715412862142976
1403715412912143104
1403715412962142976
1403715413012143104
1403715413062142976
1403715413112143104
1403715413162142976
1403715413212143104
1403715413262142976
1403715413312143104
1403715413362142976
1403715413412143104
1403715413462142976
1403715413512143104
1403715413562142976
1403715413612143104
1403715413662142976
1403715413712143104
1403715413762142976
1403715413812143104
1403715413862142976
1403715413912143104
1403715413962142976
1403715414012143104
1403715414062142976
1403715414112143104
1403715414162142976
1403715414212143104
1403715414262142976
1403715414312143104
1403715414362142976
1403715414412143104
1403715414462142976
1403715414512143104
1403715414562142976
1403715414612143104
1403715414662142976
1403715414712143104
1403715414762142976
1403715414812143104
1403715414862142976
1403715414912143104
1403715414962142976
1403715415012143104
1403715415062142976
1403715415112143104
1403715415162142976
1403715415212143104
1403715415262142976
1403715415312143104
1403715415362142976
1403715415412143104
1403715415462142976
1403715415512143104
1403715415562142976
1403715415612143104
1403715415662142976
1403715415712143104
1403715415762142976
1403715415812143104
1403715415862142976
1403715415912143104
1403715415962142976
1403715416012143104
1403715416062142976
1403715416112143104
1403715416162142976
1403715416212143104
1403715416262142976
1403715416312143104
1403715416362142976
1403715416412143104
1403715416462142976
1403715416512143104
1403715416562142976
1403715416612143104
1403715416662142976
1403715416712143104
1403715416762142976
1403715416812143104
1403715416862142976
1403715416912143104
1403715416962142976
1403715417012143104
1403715417062142976
1403715417112143104
1403715417162142976
1403715417212143104
1403715417262142976
1403715417312143104
1403715417362142976
1403715417412143104
1403715417462142976
1403715417512143104
1403715417562142976
1403715417612143104
1403715417662142976
1403715417712143104
1403715417762142976
1403715417812143104
1403715417862142976
1403715417912143104
1403715417962142976
1403715418012143104
1403715418062142976
1403715418112143104
1403715418162142976
1403715418212143104
1403715418262142976
1403715418312143104
1403715418362142976
1403715418412143104
1403715418462142976
1403715418512143104
1403715418562142976
1403715418612143104
1403715418662142976
1403715418712143104
1403715418762142976
1403715418812143104
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/V102.txt
================================================
1403715523912143104
1403715523962142976
1403715524012143104
1403715524062142976
1403715524112143104
1403715524162142976
1403715524212143104
1403715524262142976
1403715524312143104
1403715524362142976
1403715524412143104
1403715524462142976
1403715524512143104
1403715524562142976
1403715524612143104
1403715524662142976
1403715524712143104
1403715524762142976
1403715524812143104
1403715524862142976
1403715524912143104
1403715524962142976
1403715525012143104
1403715525062142976
1403715525112143104
1403715525162142976
1403715525212143104
1403715525262142976
1403715525312143104
1403715525362142976
1403715525412143104
1403715525462142976
1403715525512143104
1403715525562142976
1403715525612143104
1403715525662142976
1403715525712143104
1403715525762142976
1403715525812143104
1403715525862142976
1403715525912143104
1403715525962142976
1403715526012143104
1403715526062142976
1403715526112143104
1403715526162142976
1403715526212143104
1403715526262142976
1403715526312143104
1403715526362142976
1403715526412143104
1403715526462142976
1403715526512143104
1403715526562142976
1403715526612143104
1403715526662142976
1403715526712143104
1403715526762142976
1403715526812143104
1403715526862142976
1403715526912143104
1403715526962142976
1403715527012143104
1403715527062142976
1403715527112143104
1403715527162142976
1403715527212143104
1403715527262142976
1403715527312143104
1403715527362142976
1403715527412143104
1403715527462142976
1403715527512143104
1403715527562142976
1403715527612143104
1403715527662142976
1403715527712143104
1403715527762142976
1403715527812143104
1403715527862142976
1403715527912143104
1403715527962142976
1403715528012143104
1403715528062142976
1403715528112143104
1403715528162142976
1403715528212143104
1403715528262142976
1403715528312143104
1403715528362142976
1403715528412143104
1403715528462142976
1403715528512143104
1403715528562142976
1403715528612143104
1403715528662142976
1403715528712143104
1403715528762142976
1403715528812143104
1403715528862142976
1403715528912143104
1403715528962142976
1403715529012143104
1403715529062142976
1403715529112143104
1403715529162142976
1403715529212143104
1403715529262142976
1403715529312143104
1403715529362142976
1403715529412143104
1403715529462142976
1403715529512143104
1403715529562142976
1403715529612143104
1403715529662142976
1403715529712143104
1403715529762142976
1403715529812143104
1403715529862142976
1403715529912143104
1403715529962142976
1403715530012143104
1403715530062142976
1403715530112143104
1403715530162142976
1403715530212143104
1403715530262142976
1403715530312143104
1403715530362142976
1403715530412143104
1403715530462142976
1403715530512143104
1403715530562142976
1403715530612143104
1403715530662142976
1403715530712143104
1403715530762142976
1403715530812143104
1403715530862142976
1403715530912143104
1403715530962142976
1403715531012143104
1403715531062142976
1403715531112143104
1403715531162142976
1403715531212143104
1403715531262142976
1403715531312143104
1403715531362142976
1403715531412143104
1403715531462142976
1403715531512143104
1403715531562142976
1403715531612143104
1403715531662142976
1403715531712143104
1403715531762142976
1403715531812143104
1403715531862142976
1403715531912143104
1403715531962142976
1403715532012143104
1403715532062142976
1403715532112143104
1403715532162142976
1403715532212143104
1403715532262142976
1403715532312143104
1403715532362142976
1403715532412143104
1403715532462142976
1403715532512143104
1403715532562142976
1403715532612143104
1403715532662142976
1403715532712143104
1403715532762142976
1403715532812143104
1403715532862142976
1403715532912143104
1403715532962142976
1403715533012143104
1403715533062142976
1403715533112143104
1403715533162142976
1403715533212143104
1403715533262142976
1403715533312143104
1403715533362142976
1403715533412143104
1403715533462142976
1403715533512143104
1403715533562142976
1403715533612143104
1403715533662142976
1403715533712143104
1403715533762142976
1403715533812143104
1403715533862142976
1403715533912143104
1403715533962142976
1403715534012143104
1403715534062142976
1403715534112143104
1403715534162142976
1403715534212143104
1403715534262142976
1403715534312143104
1403715534362142976
1403715534412143104
1403715534462142976
1403715534512143104
1403715534562142976
1403715534612143104
1403715534662142976
1403715534712143104
1403715534762142976
1403715534812143104
1403715534862142976
1403715534912143104
1403715534962142976
1403715535012143104
1403715535062142976
1403715535112143104
1403715535162142976
1403715535212143104
1403715535262142976
1403715535312143104
1403715535362142976
1403715535412143104
1403715535462142976
1403715535512143104
1403715535562142976
1403715535612143104
1403715535662142976
1403715535712143104
1403715535762142976
1403715535812143104
1403715535862142976
1403715535912143104
1403715535962142976
1403715536012143104
1403715536062142976
1403715536112143104
1403715536162142976
1403715536212143104
1403715536262142976
1403715536312143104
1403715536362142976
1403715536412143104
1403715536462142976
1403715536512143104
1403715536562142976
1403715536612143104
1403715536662142976
1403715536712143104
1403715536762142976
1403715536812143104
1403715536862142976
1403715536912143104
1403715536962142976
1403715537012143104
1403715537062142976
1403715537112143104
1403715537162142976
1403715537212143104
1403715537262142976
1403715537312143104
1403715537362142976
1403715537412143104
1403715537462142976
1403715537512143104
1403715537562142976
1403715537612143104
1403715537662142976
1403715537712143104
1403715537762142976
1403715537812143104
1403715537862142976
1403715537912143104
1403715537962142976
1403715538012143104
1403715538062142976
1403715538112143104
1403715538162142976
1403715538212143104
1403715538262142976
1403715538312143104
1403715538362142976
1403715538412143104
1403715538462142976
1403715538512143104
1403715538562142976
1403715538612143104
1403715538662142976
1403715538712143104
1403715538762142976
1403715538812143104
1403715538862142976
1403715538912143104
1403715538962142976
1403715539012143104
1403715539062142976
1403715539112143104
1403715539162142976
1403715539212143104
1403715539262142976
1403715539312143104
1403715539362142976
1403715539412143104
1403715539462142976
1403715539512143104
1403715539562142976
1403715539612143104
1403715539662142976
1403715539712143104
1403715539762142976
1403715539812143104
1403715539862142976
1403715539912143104
1403715539962142976
1403715540012143104
1403715540062142976
1403715540112143104
1403715540162142976
1403715540212143104
1403715540262142976
1403715540312143104
1403715540362142976
1403715540412143104
1403715540462142976
1403715540512143104
1403715540562142976
1403715540612143104
1403715540662142976
1403715540712143104
1403715540762142976
1403715540812143104
1403715540862142976
1403715540912143104
1403715540962142976
1403715541012143104
1403715541062142976
1403715541112143104
1403715541162142976
1403715541212143104
1403715541262142976
1403715541312143104
1403715541362142976
1403715541412143104
1403715541462142976
1403715541512143104
1403715541562142976
1403715541612143104
1403715541662142976
1403715541712143104
1403715541762142976
1403715541812143104
1403715541862142976
1403715541912143104
1403715541962142976
1403715542012143104
1403715542062142976
1403715542112143104
1403715542162142976
1403715542212143104
1403715542262142976
1403715542312143104
1403715542362142976
1403715542412143104
1403715542462142976
1403715542512143104
1403715542562142976
1403715542612143104
1403715542662142976
1403715542712143104
1403715542762142976
1403715542812143104
1403715542862142976
1403715542912143104
1403715542962142976
1403715543012143104
1403715543062142976
1403715543112143104
1403715543162142976
1403715543212143104
1403715543262142976
1403715543312143104
1403715543362142976
1403715543412143104
1403715543462142976
1403715543512143104
1403715543562142976
1403715543612143104
1403715543662142976
1403715543712143104
1403715543762142976
1403715543812143104
1403715543862142976
1403715543912143104
1403715543962142976
1403715544012143104
1403715544062142976
1403715544112143104
1403715544162142976
1403715544212143104
1403715544262142976
1403715544312143104
1403715544362142976
1403715544412143104
1403715544462142976
1403715544512143104
1403715544562142976
1403715544612143104
1403715544662142976
1403715544712143104
1403715544762142976
1403715544812143104
1403715544862142976
1403715544912143104
1403715544962142976
1403715545012143104
1403715545062142976
1403715545112143104
1403715545162142976
1403715545212143104
1403715545262142976
1403715545312143104
1403715545362142976
1403715545412143104
1403715545462142976
1403715545512143104
1403715545562142976
1403715545612143104
1403715545662142976
1403715545712143104
1403715545762142976
1403715545812143104
1403715545862142976
1403715545912143104
1403715545962142976
1403715546012143104
1403715546062142976
1403715546112143104
1403715546162142976
1403715546212143104
1403715546262142976
1403715546312143104
1403715546362142976
1403715546412143104
1403715546462142976
1403715546512143104
1403715546562142976
1403715546612143104
1403715546662142976
1403715546712143104
1403715546762142976
1403715546812143104
1403715546862142976
1403715546912143104
1403715546962142976
1403715547012143104
1403715547062142976
1403715547112143104
1403715547162142976
1403715547212143104
1403715547262142976
1403715547312143104
1403715547362142976
1403715547412143104
1403715547462142976
1403715547512143104
1403715547562142976
1403715547612143104
1403715547662142976
1403715547712143104
1403715547762142976
1403715547812143104
1403715547862142976
1403715547912143104
1403715547962142976
1403715548012143104
1403715548062142976
1403715548112143104
1403715548162142976
1403715548212143104
1403715548262142976
1403715548312143104
1403715548362142976
1403715548412143104
1403715548462142976
1403715548512143104
1403715548562142976
1403715548612143104
1403715548662142976
1403715548712143104
1403715548762142976
1403715548812143104
1403715548862142976
1403715548912143104
1403715548962142976
1403715549012143104
1403715549062142976
1403715549112143104
1403715549162142976
1403715549212143104
1403715549262142976
1403715549312143104
1403715549362142976
1403715549412143104
1403715549462142976
1403715549512143104
1403715549562142976
1403715549612143104
1403715549662142976
1403715549712143104
1403715549762142976
1403715549812143104
1403715549862142976
1403715549912143104
1403715549962142976
1403715550012143104
1403715550062142976
1403715550112143104
1403715550162142976
1403715550212143104
1403715550262142976
1403715550312143104
1403715550362142976
1403715550412143104
1403715550462142976
1403715550512143104
1403715550562142976
1403715550612143104
1403715550662142976
1403715550712143104
1403715550762142976
1403715550812143104
1403715550862142976
1403715550912143104
1403715550962142976
1403715551012143104
1403715551062142976
1403715551112143104
1403715551162142976
1403715551212143104
1403715551262142976
1403715551312143104
1403715551362142976
1403715551412143104
1403715551462142976
1403715551512143104
1403715551562142976
1403715551612143104
1403715551662142976
1403715551712143104
1403715551762142976
1403715551812143104
1403715551862142976
1403715551912143104
1403715551962142976
1403715552012143104
1403715552062142976
1403715552112143104
1403715552162142976
1403715552212143104
1403715552262142976
1403715552312143104
1403715552362142976
1403715552412143104
1403715552462142976
1403715552512143104
1403715552562142976
1403715552612143104
1403715552662142976
1403715552712143104
1403715552762142976
1403715552812143104
1403715552862142976
1403715552912143104
1403715552962142976
1403715553012143104
1403715553062142976
1403715553112143104
1403715553162142976
1403715553212143104
1403715553262142976
1403715553312143104
1403715553362142976
1403715553412143104
1403715553462142976
1403715553512143104
1403715553562142976
1403715553612143104
1403715553662142976
1403715553712143104
1403715553762142976
1403715553812143104
1403715553862142976
1403715553912143104
1403715553962142976
1403715554012143104
1403715554062142976
1403715554112143104
1403715554162142976
1403715554212143104
1403715554262142976
1403715554312143104
1403715554362142976
1403715554412143104
1403715554462142976
1403715554512143104
1403715554562142976
1403715554612143104
1403715554662142976
1403715554712143104
1403715554762142976
1403715554812143104
1403715554862142976
1403715554912143104
1403715554962142976
1403715555012143104
1403715555062142976
1403715555112143104
1403715555162142976
1403715555212143104
1403715555262142976
1403715555312143104
1403715555362142976
1403715555412143104
1403715555462142976
1403715555512143104
1403715555562142976
1403715555612143104
1403715555662142976
1403715555712143104
1403715555762142976
1403715555812143104
1403715555862142976
1403715555912143104
1403715555962142976
1403715556012143104
1403715556062142976
1403715556112143104
1403715556162142976
1403715556212143104
1403715556262142976
1403715556312143104
1403715556362142976
1403715556412143104
1403715556462142976
1403715556512143104
1403715556562142976
1403715556612143104
1403715556662142976
1403715556712143104
1403715556762142976
1403715556812143104
1403715556862142976
1403715556912143104
1403715556962142976
1403715557012143104
1403715557062142976
1403715557112143104
1403715557162142976
1403715557212143104
1403715557262142976
1403715557312143104
1403715557362142976
1403715557412143104
1403715557462142976
1403715557512143104
1403715557562142976
1403715557612143104
1403715557662142976
1403715557712143104
1403715557762142976
1403715557812143104
1403715557862142976
1403715557912143104
1403715557962142976
1403715558012143104
1403715558062142976
1403715558112143104
1403715558162142976
1403715558212143104
1403715558262142976
1403715558312143104
1403715558362142976
1403715558412143104
1403715558462142976
1403715558512143104
1403715558562142976
1403715558612143104
1403715558662142976
1403715558712143104
1403715558762142976
1403715558812143104
1403715558862142976
1403715558912143104
1403715558962142976
1403715559012143104
1403715559062142976
1403715559112143104
1403715559162142976
1403715559212143104
1403715559262142976
1403715559312143104
1403715559362142976
1403715559412143104
1403715559462142976
1403715559512143104
1403715559562142976
1403715559612143104
1403715559662142976
1403715559712143104
1403715559762142976
1403715559812143104
1403715559862142976
1403715559912143104
1403715559962142976
1403715560012143104
1403715560062142976
1403715560112143104
1403715560162142976
1403715560212143104
1403715560262142976
1403715560312143104
1403715560362142976
1403715560412143104
1403715560462142976
1403715560512143104
1403715560562142976
1403715560612143104
1403715560662142976
1403715560712143104
1403715560762142976
1403715560812143104
1403715560862142976
1403715560912143104
1403715560962142976
1403715561012143104
1403715561062142976
1403715561112143104
1403715561162142976
1403715561212143104
1403715561262142976
1403715561312143104
1403715561362142976
1403715561412143104
1403715561462142976
1403715561512143104
1403715561562142976
1403715561612143104
1403715561662142976
1403715561712143104
1403715561762142976
1403715561812143104
1403715561862142976
1403715561912143104
1403715561962142976
1403715562012143104
1403715562062142976
1403715562112143104
1403715562162142976
1403715562212143104
1403715562262142976
1403715562312143104
1403715562362142976
1403715562412143104
1403715562462142976
1403715562512143104
1403715562562142976
1403715562612143104
1403715562662142976
1403715562712143104
1403715562762142976
1403715562812143104
1403715562862142976
1403715562912143104
1403715562962142976
1403715563012143104
1403715563062142976
1403715563112143104
1403715563162142976
1403715563212143104
1403715563262142976
1403715563312143104
1403715563362142976
1403715563412143104
1403715563462142976
1403715563512143104
1403715563562142976
1403715563612143104
1403715563662142976
1403715563712143104
1403715563762142976
1403715563812143104
1403715563862142976
1403715563912143104
1403715563962142976
1403715564012143104
1403715564062142976
1403715564112143104
1403715564162142976
1403715564212143104
1403715564262142976
1403715564312143104
1403715564362142976
1403715564412143104
1403715564462142976
1403715564512143104
1403715564562142976
1403715564612143104
1403715564662142976
1403715564712143104
1403715564762142976
1403715564812143104
1403715564862142976
1403715564912143104
1403715564962142976
1403715565012143104
1403715565062142976
1403715565112143104
1403715565162142976
1403715565212143104
1403715565262142976
1403715565312143104
1403715565362142976
1403715565412143104
1403715565462142976
1403715565512143104
1403715565562142976
1403715565612143104
1403715565662142976
1403715565712143104
1403715565762142976
1403715565812143104
1403715565862142976
1403715565912143104
1403715565962142976
1403715566012143104
1403715566062142976
1403715566112143104
1403715566162142976
1403715566212143104
1403715566262142976
1403715566312143104
1403715566362142976
1403715566412143104
1403715566462142976
1403715566512143104
1403715566562142976
1403715566612143104
1403715566662142976
1403715566712143104
1403715566762142976
1403715566812143104
1403715566862142976
1403715566912143104
1403715566962142976
1403715567012143104
1403715567062142976
1403715567112143104
1403715567162142976
1403715567212143104
1403715567262142976
1403715567312143104
1403715567362142976
1403715567412143104
1403715567462142976
1403715567512143104
1403715567562142976
1403715567612143104
1403715567662142976
1403715567712143104
1403715567762142976
1403715567812143104
1403715567862142976
1403715567912143104
1403715567962142976
1403715568012143104
1403715568062142976
1403715568112143104
1403715568162142976
1403715568212143104
1403715568262142976
1403715568312143104
1403715568362142976
1403715568412143104
1403715568462142976
1403715568512143104
1403715568562142976
1403715568612143104
1403715568662142976
1403715568712143104
1403715568762142976
1403715568812143104
1403715568862142976
1403715568912143104
1403715568962142976
1403715569012143104
1403715569062142976
1403715569112143104
1403715569162142976
1403715569212143104
1403715569262142976
1403715569312143104
1403715569362142976
1403715569412143104
1403715569462142976
1403715569512143104
1403715569562142976
1403715569612143104
1403715569662142976
1403715569712143104
1403715569762142976
1403715569812143104
1403715569862142976
1403715569912143104
1403715569962142976
1403715570012143104
1403715570062142976
1403715570112143104
1403715570162142976
1403715570212143104
1403715570262142976
1403715570312143104
1403715570362142976
1403715570412143104
1403715570462142976
1403715570512143104
1403715570562142976
1403715570612143104
1403715570662142976
1403715570712143104
1403715570762142976
1403715570812143104
1403715570862142976
1403715570912143104
1403715570962142976
1403715571012143104
1403715571062142976
1403715571112143104
1403715571162142976
1403715571212143104
1403715571262142976
1403715571312143104
1403715571362142976
1403715571412143104
1403715571462142976
1403715571512143104
1403715571562142976
1403715571612143104
1403715571662142976
1403715571712143104
1403715571762142976
1403715571812143104
1403715571862142976
1403715571912143104
1403715571962142976
1403715572012143104
1403715572062142976
1403715572112143104
1403715572162142976
1403715572212143104
1403715572262142976
1403715572312143104
1403715572362142976
1403715572412143104
1403715572462142976
1403715572512143104
1403715572562142976
1403715572612143104
1403715572662142976
1403715572712143104
1403715572762142976
1403715572812143104
1403715572862142976
1403715572912143104
1403715572962142976
1403715573012143104
1403715573062142976
1403715573112143104
1403715573162142976
1403715573212143104
1403715573262142976
1403715573312143104
1403715573362142976
1403715573412143104
1403715573462142976
1403715573512143104
1403715573562142976
1403715573612143104
1403715573662142976
1403715573712143104
1403715573762142976
1403715573812143104
1403715573862142976
1403715573912143104
1403715573962142976
1403715574012143104
1403715574062142976
1403715574112143104
1403715574162142976
1403715574212143104
1403715574262142976
1403715574312143104
1403715574362142976
1403715574412143104
1403715574462142976
1403715574512143104
1403715574562142976
1403715574612143104
1403715574662142976
1403715574712143104
1403715574762142976
1403715574812143104
1403715574862142976
1403715574912143104
1403715574962142976
1403715575012143104
1403715575062142976
1403715575112143104
1403715575162142976
1403715575212143104
1403715575262142976
1403715575312143104
1403715575362142976
1403715575412143104
1403715575462142976
1403715575512143104
1403715575562142976
1403715575612143104
1403715575662142976
1403715575712143104
1403715575762142976
1403715575812143104
1403715575862142976
1403715575912143104
1403715575962142976
1403715576012143104
1403715576062142976
1403715576112143104
1403715576162142976
1403715576212143104
1403715576262142976
1403715576312143104
1403715576362142976
1403715576412143104
1403715576462142976
1403715576512143104
1403715576562142976
1403715576612143104
1403715576662142976
1403715576712143104
1403715576762142976
1403715576812143104
1403715576862142976
1403715576912143104
1403715576962142976
1403715577012143104
1403715577062142976
1403715577112143104
1403715577162142976
1403715577212143104
1403715577262142976
1403715577312143104
1403715577362142976
1403715577412143104
1403715577462142976
1403715577512143104
1403715577562142976
1403715577612143104
1403715577662142976
1403715577712143104
1403715577762142976
1403715577812143104
1403715577862142976
1403715577912143104
1403715577962142976
1403715578012143104
1403715578062142976
1403715578112143104
1403715578162142976
1403715578212143104
1403715578262142976
1403715578312143104
1403715578362142976
1403715578412143104
1403715578462142976
1403715578512143104
1403715578562142976
1403715578612143104
1403715578662142976
1403715578712143104
1403715578762142976
1403715578812143104
1403715578862142976
1403715578912143104
1403715578962142976
1403715579012143104
1403715579062142976
1403715579112143104
1403715579162142976
1403715579212143104
1403715579262142976
1403715579312143104
1403715579362142976
1403715579412143104
1403715579462142976
1403715579512143104
1403715579562142976
1403715579612143104
1403715579662142976
1403715579712143104
1403715579762142976
1403715579812143104
1403715579862142976
1403715579912143104
1403715579962142976
1403715580012143104
1403715580062142976
1403715580112143104
1403715580162142976
1403715580212143104
1403715580262142976
1403715580312143104
1403715580362142976
1403715580412143104
1403715580462142976
1403715580512143104
1403715580562142976
1403715580612143104
1403715580662142976
1403715580712143104
1403715580762142976
1403715580812143104
1403715580862142976
1403715580912143104
1403715580962142976
1403715581012143104
1403715581062142976
1403715581112143104
1403715581162142976
1403715581212143104
1403715581262142976
1403715581312143104
1403715581362142976
1403715581412143104
1403715581462142976
1403715581512143104
1403715581562142976
1403715581612143104
1403715581662142976
1403715581712143104
1403715581762142976
1403715581812143104
1403715581862142976
1403715581912143104
1403715581962142976
1403715582012143104
1403715582062142976
1403715582112143104
1403715582162142976
1403715582212143104
1403715582262142976
1403715582312143104
1403715582362142976
1403715582412143104
1403715582462142976
1403715582512143104
1403715582562142976
1403715582612143104
1403715582662142976
1403715582712143104
1403715582762142976
1403715582812143104
1403715582862142976
1403715582912143104
1403715582962142976
1403715583012143104
1403715583062142976
1403715583112143104
1403715583162142976
1403715583212143104
1403715583262142976
1403715583312143104
1403715583362142976
1403715583412143104
1403715583462142976
1403715583512143104
1403715583562142976
1403715583612143104
1403715583662142976
1403715583712143104
1403715583762142976
1403715583812143104
1403715583862142976
1403715583912143104
1403715583962142976
1403715584012143104
1403715584062142976
1403715584112143104
1403715584162142976
1403715584212143104
1403715584262142976
1403715584312143104
1403715584362142976
1403715584412143104
1403715584462142976
1403715584512143104
1403715584562142976
1403715584612143104
1403715584662142976
1403715584712143104
1403715584762142976
1403715584812143104
1403715584862142976
1403715584912143104
1403715584962142976
1403715585012143104
1403715585062142976
1403715585112143104
1403715585162142976
1403715585212143104
1403715585262142976
1403715585312143104
1403715585362142976
1403715585412143104
1403715585462142976
1403715585512143104
1403715585562142976
1403715585612143104
1403715585662142976
1403715585712143104
1403715585762142976
1403715585812143104
1403715585862142976
1403715585912143104
1403715585962142976
1403715586012143104
1403715586062142976
1403715586112143104
1403715586162142976
1403715586212143104
1403715586262142976
1403715586312143104
1403715586362142976
1403715586412143104
1403715586462142976
1403715586512143104
1403715586562142976
1403715586612143104
1403715586662142976
1403715586712143104
1403715586762142976
1403715586812143104
1403715586862142976
1403715586912143104
1403715586962142976
1403715587012143104
1403715587062142976
1403715587112143104
1403715587162142976
1403715587212143104
1403715587262142976
1403715587312143104
1403715587362142976
1403715587412143104
1403715587462142976
1403715587512143104
1403715587562142976
1403715587612143104
1403715587662142976
1403715587712143104
1403715587762142976
1403715587812143104
1403715587862142976
1403715587912143104
1403715587962142976
1403715588012143104
1403715588062142976
1403715588112143104
1403715588162142976
1403715588212143104
1403715588262142976
1403715588312143104
1403715588362142976
1403715588412143104
1403715588462142976
1403715588512143104
1403715588562142976
1403715588612143104
1403715588662142976
1403715588712143104
1403715588762142976
1403715588812143104
1403715588862142976
1403715588912143104
1403715588962142976
1403715589012143104
1403715589062142976
1403715589112143104
1403715589162142976
1403715589212143104
1403715589262142976
1403715589312143104
1403715589362142976
1403715589412143104
1403715589462142976
1403715589512143104
1403715589562142976
1403715589612143104
1403715589662142976
1403715589712143104
1403715589762142976
1403715589812143104
1403715589862142976
1403715589912143104
1403715589962142976
1403715590012143104
1403715590062142976
1403715590112143104
1403715590162142976
1403715590212143104
1403715590262142976
1403715590312143104
1403715590362142976
1403715590412143104
1403715590462142976
1403715590512143104
1403715590562142976
1403715590612143104
1403715590662142976
1403715590712143104
1403715590762142976
1403715590812143104
1403715590862142976
1403715590912143104
1403715590962142976
1403715591012143104
1403715591062142976
1403715591112143104
1403715591162142976
1403715591212143104
1403715591262142976
1403715591312143104
1403715591362142976
1403715591412143104
1403715591462142976
1403715591512143104
1403715591562142976
1403715591612143104
1403715591662142976
1403715591712143104
1403715591762142976
1403715591812143104
1403715591862142976
1403715591912143104
1403715591962142976
1403715592012143104
1403715592062142976
1403715592112143104
1403715592162142976
1403715592212143104
1403715592262142976
1403715592312143104
1403715592362142976
1403715592412143104
1403715592462142976
1403715592512143104
1403715592562142976
1403715592612143104
1403715592662142976
1403715592712143104
1403715592762142976
1403715592812143104
1403715592862142976
1403715592912143104
1403715592962142976
1403715593012143104
1403715593062142976
1403715593112143104
1403715593162142976
1403715593212143104
1403715593262142976
1403715593312143104
1403715593362142976
1403715593412143104
1403715593462142976
1403715593512143104
1403715593562142976
1403715593612143104
1403715593662142976
1403715593712143104
1403715593762142976
1403715593812143104
1403715593862142976
1403715593912143104
1403715593962142976
1403715594012143104
1403715594062142976
1403715594112143104
1403715594162142976
1403715594212143104
1403715594262142976
1403715594312143104
1403715594362142976
1403715594412143104
1403715594462142976
1403715594512143104
1403715594562142976
1403715594612143104
1403715594662142976
1403715594712143104
1403715594762142976
1403715594812143104
1403715594862142976
1403715594912143104
1403715594962142976
1403715595012143104
1403715595062142976
1403715595112143104
1403715595162142976
1403715595212143104
1403715595262142976
1403715595312143104
1403715595362142976
1403715595412143104
1403715595462142976
1403715595512143104
1403715595562142976
1403715595612143104
1403715595662142976
1403715595712143104
1403715595762142976
1403715595812143104
1403715595862142976
1403715595912143104
1403715595962142976
1403715596012143104
1403715596062142976
1403715596112143104
1403715596162142976
1403715596212143104
1403715596262142976
1403715596312143104
1403715596362142976
1403715596412143104
1403715596462142976
1403715596512143104
1403715596562142976
1403715596612143104
1403715596662142976
1403715596712143104
1403715596762142976
1403715596812143104
1403715596862142976
1403715596912143104
1403715596962142976
1403715597012143104
1403715597062142976
1403715597112143104
1403715597162142976
1403715597212143104
1403715597262142976
1403715597312143104
1403715597362142976
1403715597412143104
1403715597462142976
1403715597512143104
1403715597562142976
1403715597612143104
1403715597662142976
1403715597712143104
1403715597762142976
1403715597812143104
1403715597862142976
1403715597912143104
1403715597962142976
1403715598012143104
1403715598062142976
1403715598112143104
1403715598162142976
1403715598212143104
1403715598262142976
1403715598312143104
1403715598362142976
1403715598412143104
1403715598462142976
1403715598512143104
1403715598562142976
1403715598612143104
1403715598662142976
1403715598712143104
1403715598762142976
1403715598812143104
1403715598862142976
1403715598912143104
1403715598962142976
1403715599012143104
1403715599062142976
1403715599112143104
1403715599162142976
1403715599212143104
1403715599262142976
1403715599312143104
1403715599362142976
1403715599412143104
1403715599462142976
1403715599512143104
1403715599562142976
1403715599612143104
1403715599662142976
1403715599712143104
1403715599762142976
1403715599812143104
1403715599862142976
1403715599912143104
1403715599962142976
1403715600012143104
1403715600062142976
1403715600112143104
1403715600162142976
1403715600212143104
1403715600262142976
1403715600312143104
1403715600362142976
1403715600412143104
1403715600462142976
1403715600512143104
1403715600562142976
1403715600612143104
1403715600662142976
1403715600712143104
1403715600762142976
1403715600812143104
1403715600862142976
1403715600912143104
1403715600962142976
1403715601012143104
1403715601062142976
1403715601112143104
1403715601162142976
1403715601212143104
1403715601262142976
1403715601312143104
1403715601362142976
1403715601412143104
1403715601462142976
1403715601512143104
1403715601562142976
1403715601612143104
1403715601662142976
1403715601712143104
1403715601762142976
1403715601812143104
1403715601862142976
1403715601912143104
1403715601962142976
1403715602012143104
1403715602062142976
1403715602112143104
1403715602162142976
1403715602212143104
1403715602262142976
1403715602312143104
1403715602362142976
1403715602412143104
1403715602462142976
1403715602512143104
1403715602562142976
1403715602612143104
1403715602662142976
1403715602712143104
1403715602762142976
1403715602812143104
1403715602862142976
1403715602912143104
1403715602962142976
1403715603012143104
1403715603062142976
1403715603112143104
1403715603162142976
1403715603212143104
1403715603262142976
1403715603312143104
1403715603362142976
1403715603412143104
1403715603462142976
1403715603512143104
1403715603562142976
1403715603612143104
1403715603662142976
1403715603712143104
1403715603762142976
1403715603812143104
1403715603862142976
1403715603912143104
1403715603962142976
1403715604012143104
1403715604062142976
1403715604112143104
1403715604162142976
1403715604212143104
1403715604262142976
1403715604312143104
1403715604362142976
1403715604412143104
1403715604462142976
1403715604512143104
1403715604562142976
1403715604612143104
1403715604662142976
1403715604712143104
1403715604762142976
1403715604812143104
1403715604862142976
1403715604912143104
1403715604962142976
1403715605012143104
1403715605062142976
1403715605112143104
1403715605162142976
1403715605212143104
1403715605262142976
1403715605312143104
1403715605362142976
1403715605412143104
1403715605462142976
1403715605512143104
1403715605562142976
1403715605612143104
1403715605662142976
1403715605712143104
1403715605762142976
1403715605812143104
1403715605862142976
1403715605912143104
1403715605962142976
1403715606012143104
1403715606062142976
1403715606112143104
1403715606162142976
1403715606212143104
1403715606262142976
1403715606312143104
1403715606362142976
1403715606412143104
1403715606462142976
1403715606512143104
1403715606562142976
1403715606612143104
1403715606662142976
1403715606712143104
1403715606762142976
1403715606812143104
1403715606862142976
1403715606912143104
1403715606962142976
1403715607012143104
1403715607062142976
1403715607112143104
1403715607162142976
1403715607212143104
1403715607262142976
1403715607312143104
1403715607362142976
1403715607412143104
1403715607462142976
1403715607512143104
1403715607562142976
1403715607612143104
1403715607662142976
1403715607712143104
1403715607762142976
1403715607812143104
1403715607862142976
1403715607912143104
1403715607962142976
1403715608012143104
1403715608062142976
1403715608112143104
1403715608162142976
1403715608212143104
1403715608262142976
1403715608312143104
1403715608362142976
1403715608412143104
1403715608462142976
1403715608512143104
1403715608562142976
1403715608612143104
1403715608662142976
1403715608712143104
1403715608762142976
1403715608812143104
1403715608862142976
1403715608912143104
1403715608962142976
1403715609012143104
1403715609062142976
1403715609112143104
1403715609162142976
1403715609212143104
1403715609262142976
1403715609312143104
1403715609362142976
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/V103.txt
================================================
1403715886584058112
1403715886634057984
1403715886684058112
1403715886734057984
1403715886784058112
1403715886834057984
1403715886884058112
1403715886934057984
1403715886984058112
1403715887034057984
1403715887084058112
1403715887134057984
1403715887184058112
1403715887234057984
1403715887284058112
1403715887334057984
1403715887384058112
1403715887434057984
1403715887484058112
1403715887534057984
1403715887584058112
1403715887634057984
1403715887684058112
1403715887734057984
1403715887784058112
1403715887834057984
1403715887884058112
1403715887934057984
1403715887984058112
1403715888034057984
1403715888084058112
1403715888134057984
1403715888184058112
1403715888234057984
1403715888284058112
1403715888334057984
1403715888384058112
1403715888434057984
1403715888484058112
1403715888534057984
1403715888584058112
1403715888634057984
1403715888684058112
1403715888734057984
1403715888784058112
1403715888834057984
1403715888884058112
1403715888934057984
1403715888984058112
1403715889034057984
1403715889084058112
1403715889134057984
1403715889184058112
1403715889234057984
1403715889284058112
1403715889334057984
1403715889384058112
1403715889434057984
1403715889484058112
1403715889534057984
1403715889584058112
1403715889634057984
1403715889684058112
1403715889734057984
1403715889784058112
1403715889834057984
1403715889884058112
1403715889934057984
1403715889984058112
1403715890034057984
1403715890084058112
1403715890134057984
1403715890184058112
1403715890234057984
1403715890284058112
1403715890334057984
1403715890384058112
1403715890434057984
1403715890484058112
1403715890534057984
1403715890584058112
1403715890634057984
1403715890684058112
1403715890734057984
1403715890784058112
1403715890834057984
1403715890884058112
1403715890934057984
1403715890984058112
1403715891034057984
1403715891084058112
1403715891134057984
1403715891184058112
1403715891234057984
1403715891284058112
1403715891334057984
1403715891384058112
1403715891434057984
1403715891484058112
1403715891534057984
1403715891584058112
1403715891634057984
1403715891684058112
1403715891734057984
1403715891784058112
1403715891834057984
1403715891884058112
1403715891934057984
1403715891984058112
1403715892034057984
1403715892084058112
1403715892134057984
1403715892184058112
1403715892234057984
1403715892284058112
1403715892334057984
1403715892384058112
1403715892434057984
1403715892484058112
1403715892534057984
1403715892584058112
1403715892634057984
1403715892684058112
1403715892734057984
1403715892784058112
1403715892834057984
1403715892884058112
1403715892934057984
1403715892984058112
1403715893034057984
1403715893084058112
1403715893134057984
1403715893184058112
1403715893234057984
1403715893284058112
1403715893334057984
1403715893384058112
1403715893434057984
1403715893484058112
1403715893534057984
1403715893584058112
1403715893634057984
1403715893684058112
1403715893734057984
1403715893784058112
1403715893834057984
1403715893884058112
1403715893934057984
1403715893984058112
1403715894034057984
1403715894084058112
1403715894134057984
1403715894184058112
1403715894234057984
1403715894284058112
1403715894334057984
1403715894384058112
1403715894434057984
1403715894484058112
1403715894534057984
1403715894584058112
1403715894634057984
1403715894684058112
1403715894734057984
1403715894784058112
1403715894834057984
1403715894884058112
1403715894934057984
1403715894984058112
1403715895034057984
1403715895084058112
1403715895134057984
1403715895184058112
1403715895234057984
1403715895284058112
1403715895334057984
1403715895384058112
1403715895434057984
1403715895484058112
1403715895534057984
1403715895584058112
1403715895634057984
1403715895684058112
1403715895734057984
1403715895784058112
1403715895834057984
1403715895884058112
1403715895934057984
1403715895984058112
1403715896034057984
1403715896084058112
1403715896134057984
1403715896184058112
1403715896234057984
1403715896284058112
1403715896334057984
1403715896384058112
1403715896434057984
1403715896484058112
1403715896534057984
1403715896584058112
1403715896634057984
1403715896684058112
1403715896734057984
1403715896784058112
1403715896834057984
1403715896884058112
1403715896934057984
1403715896984058112
1403715897034057984
1403715897084058112
1403715897134057984
1403715897184058112
1403715897234057984
1403715897284058112
1403715897334057984
1403715897384058112
1403715897434057984
1403715897484058112
1403715897534057984
1403715897584058112
1403715897634057984
1403715897684058112
1403715897734057984
1403715897784058112
1403715897834057984
1403715897884058112
1403715897934057984
1403715897984058112
1403715898034057984
1403715898084058112
1403715898134057984
1403715898184058112
1403715898234057984
1403715898284058112
1403715898334057984
1403715898384058112
1403715898434057984
1403715898484058112
1403715898534057984
1403715898584058112
1403715898634057984
1403715898684058112
1403715898734057984
1403715898784058112
1403715898834057984
1403715898884058112
1403715898934057984
1403715898984058112
1403715899034057984
1403715899084058112
1403715899134057984
1403715899184058112
1403715899234057984
1403715899284058112
1403715899334057984
1403715899384058112
1403715899434057984
1403715899484058112
1403715899534057984
1403715899584058112
1403715899634057984
1403715899684058112
1403715899734057984
1403715899784058112
1403715899834057984
1403715899884058112
1403715899934057984
1403715899984058112
1403715900034057984
1403715900084058112
1403715900134057984
1403715900184058112
1403715900234057984
1403715900284058112
1403715900334057984
1403715900384058112
1403715900434057984
1403715900484058112
1403715900534057984
1403715900584058112
1403715900634057984
1403715900684058112
1403715900734057984
1403715900784058112
1403715900834057984
1403715900884058112
1403715900934057984
1403715900984058112
1403715901034057984
1403715901084058112
1403715901134057984
1403715901184058112
1403715901234057984
1403715901284058112
1403715901334057984
1403715901384058112
1403715901434057984
1403715901484058112
1403715901534057984
1403715901584058112
1403715901634057984
1403715901684058112
1403715901734057984
1403715901784058112
1403715901834057984
1403715901884058112
1403715901934057984
1403715901984058112
1403715902034057984
1403715902084058112
1403715902134057984
1403715902184058112
1403715902234057984
1403715902284058112
1403715902334057984
1403715902384058112
1403715902434057984
1403715902484058112
1403715902534057984
1403715902584058112
1403715902634057984
1403715902684058112
1403715902734057984
1403715902784058112
1403715902834057984
1403715902884058112
1403715902934057984
1403715902984058112
1403715903034057984
1403715903084058112
1403715903134057984
1403715903184058112
1403715903234057984
1403715903284058112
1403715903334057984
1403715903384058112
1403715903434057984
1403715903484058112
1403715903534057984
1403715903584058112
1403715903634057984
1403715903684058112
1403715903734057984
1403715903784058112
1403715903834057984
1403715903884058112
1403715903934057984
1403715903984058112
1403715904034057984
1403715904084058112
1403715904134057984
1403715904184058112
1403715904234057984
1403715904284058112
1403715904334057984
1403715904384058112
1403715904434057984
1403715904484058112
1403715904534057984
1403715904584058112
1403715904634057984
1403715904684058112
1403715904734057984
1403715904784058112
1403715904834057984
1403715904884058112
1403715904934057984
1403715904984058112
1403715905034057984
1403715905084058112
1403715905134057984
1403715905184058112
1403715905234057984
1403715905284058112
1403715905334057984
1403715905384058112
1403715905434057984
1403715905484058112
1403715905534057984
1403715905584058112
1403715905634057984
1403715905684058112
1403715905734057984
1403715905784058112
1403715905834057984
1403715905884058112
1403715905934057984
1403715905984058112
1403715906034057984
1403715906084058112
1403715906134057984
1403715906184058112
1403715906234057984
1403715906284058112
1403715906334057984
1403715906384058112
1403715906434057984
1403715906484058112
1403715906534057984
1403715906584058112
1403715906634057984
1403715906684058112
1403715906734057984
1403715906784058112
1403715906834057984
1403715906884058112
1403715906934057984
1403715906984058112
1403715907034057984
1403715907084058112
1403715907134057984
1403715907184058112
1403715907234057984
1403715907284058112
1403715907334057984
1403715907384058112
1403715907434057984
1403715907484058112
1403715907534057984
1403715907584058112
1403715907634057984
1403715907684058112
1403715907734057984
1403715907784058112
1403715907834057984
1403715907884058112
1403715907934057984
1403715907984058112
1403715908034057984
1403715908084058112
1403715908134057984
1403715908184058112
1403715908234057984
1403715908284058112
1403715908334057984
1403715908384058112
1403715908434057984
1403715908484058112
1403715908534057984
1403715908584058112
1403715908634057984
1403715908684058112
1403715908734057984
1403715908784058112
1403715908834057984
1403715908884058112
1403715908934057984
1403715908984058112
1403715909034057984
1403715909084058112
1403715909134057984
1403715909184058112
1403715909234057984
1403715909284058112
1403715909334057984
1403715909384058112
1403715909434057984
1403715909484058112
1403715909534057984
1403715909584058112
1403715909634057984
1403715909684058112
1403715909734057984
1403715909784058112
1403715909834057984
1403715909884058112
1403715909934057984
1403715909984058112
1403715910034057984
1403715910084058112
1403715910134057984
1403715910184058112
1403715910234057984
1403715910284058112
1403715910334057984
1403715910384058112
1403715910434057984
1403715910484058112
1403715910534057984
1403715910584058112
1403715910634057984
1403715910684058112
1403715910734057984
1403715910784058112
1403715910834057984
1403715910884058112
1403715910934057984
1403715910984058112
1403715911034057984
1403715911084058112
1403715911134057984
1403715911184058112
1403715911234057984
1403715911284058112
1403715911334057984
1403715911384058112
1403715911434057984
1403715911484058112
1403715911534057984
1403715911584058112
1403715911634057984
1403715911684058112
1403715911734057984
1403715911784058112
1403715911834057984
1403715911884058112
1403715911934057984
1403715911984058112
1403715912034057984
1403715912084058112
1403715912134057984
1403715912184058112
1403715912234057984
1403715912284058112
1403715912334057984
1403715912384058112
1403715912434057984
1403715912484058112
1403715912534057984
1403715912584058112
1403715912634057984
1403715912684058112
1403715912734057984
1403715912784058112
1403715912834057984
1403715912884058112
1403715912934057984
1403715912984058112
1403715913034057984
1403715913084058112
1403715913134057984
1403715913184058112
1403715913234057984
1403715913284058112
1403715913334057984
1403715913384058112
1403715913434057984
1403715913484058112
1403715913534057984
1403715913584058112
1403715913634057984
1403715913684058112
1403715913734057984
1403715913784058112
1403715913834057984
1403715913884058112
1403715913934057984
1403715913984058112
1403715914034057984
1403715914084058112
1403715914134057984
1403715914184058112
1403715914234057984
1403715914284058112
1403715914334057984
1403715914384058112
1403715914434057984
1403715914484058112
1403715914534057984
1403715914584058112
1403715914634057984
1403715914684058112
1403715914734057984
1403715914784058112
1403715914834057984
1403715914884058112
1403715914934057984
1403715914984058112
1403715915034057984
1403715915084058112
1403715915134057984
1403715915184058112
1403715915234057984
1403715915284058112
1403715915334057984
1403715915384058112
1403715915434057984
1403715915484058112
1403715915534057984
1403715915584058112
1403715915634057984
1403715915684058112
1403715915734057984
1403715915784058112
1403715915834057984
1403715915884058112
1403715915934057984
1403715915984058112
1403715916034057984
1403715916084058112
1403715916134057984
1403715916184058112
1403715916234057984
1403715916284058112
1403715916334057984
1403715916384058112
1403715916434057984
1403715916484058112
1403715916534057984
1403715916584058112
1403715916634057984
1403715916684058112
1403715916734057984
1403715916784058112
1403715916834057984
1403715916884058112
1403715916934057984
1403715916984058112
1403715917034057984
1403715917084058112
1403715917134057984
1403715917184058112
1403715917234057984
1403715917284058112
1403715917334057984
1403715917384058112
1403715917434057984
1403715917484058112
1403715917534057984
1403715917584058112
1403715917634057984
1403715917684058112
1403715917734057984
1403715917784058112
1403715917834057984
1403715917884058112
1403715917934057984
1403715917984058112
1403715918034057984
1403715918084058112
1403715918134057984
1403715918184058112
1403715918234057984
1403715918284058112
1403715918334057984
1403715918384058112
1403715918434057984
1403715918484058112
1403715918534057984
1403715918584058112
1403715918634057984
1403715918684058112
1403715918734057984
1403715918784058112
1403715918834057984
1403715918884058112
1403715918934057984
1403715918984058112
1403715919034057984
1403715919084058112
1403715919134057984
1403715919184058112
1403715919234057984
1403715919284058112
1403715919334057984
1403715919384058112
1403715919434057984
1403715919484058112
1403715919534057984
1403715919584058112
1403715919634057984
1403715919684058112
1403715919734057984
1403715919784058112
1403715919834057984
1403715919884058112
1403715919934057984
1403715919984058112
1403715920034057984
1403715920084058112
1403715920134057984
1403715920184058112
1403715920234057984
1403715920284058112
1403715920334057984
1403715920384058112
1403715920434057984
1403715920484058112
1403715920534057984
1403715920584058112
1403715920634057984
1403715920684058112
1403715920734057984
1403715920784058112
1403715920834057984
1403715920884058112
1403715920934057984
1403715920984058112
1403715921034057984
1403715921084058112
1403715921134057984
1403715921184058112
1403715921234057984
1403715921284058112
1403715921334057984
1403715921384058112
1403715921434057984
1403715921484058112
1403715921534057984
1403715921584058112
1403715921634057984
1403715921684058112
1403715921734057984
1403715921784058112
1403715921834057984
1403715921884058112
1403715921934057984
1403715921984058112
1403715922034057984
1403715922084058112
1403715922134057984
1403715922184058112
1403715922234057984
1403715922284058112
1403715922334057984
1403715922384058112
1403715922434057984
1403715922484058112
1403715922534057984
1403715922584058112
1403715922634057984
1403715922684058112
1403715922734057984
1403715922784058112
1403715922834057984
1403715922884058112
1403715922934057984
1403715922984058112
1403715923034057984
1403715923084058112
1403715923134057984
1403715923184058112
1403715923234057984
1403715923284058112
1403715923334057984
1403715923384058112
1403715923434057984
1403715923484058112
1403715923534057984
1403715923584058112
1403715923634057984
1403715923684058112
1403715923734057984
1403715923784058112
1403715923834057984
1403715923884058112
1403715923934057984
1403715923984058112
1403715924034057984
1403715924084058112
1403715924134057984
1403715924184058112
1403715924234057984
1403715924284058112
1403715924334057984
1403715924384058112
1403715924434057984
1403715924484058112
1403715924534057984
1403715924584058112
1403715924634057984
1403715924684058112
1403715924734057984
1403715924784058112
1403715924834057984
1403715924884058112
1403715924934057984
1403715924984058112
1403715925034057984
1403715925084058112
1403715925134057984
1403715925184058112
1403715925234057984
1403715925284058112
1403715925334057984
1403715925384058112
1403715925434057984
1403715925484058112
1403715925534057984
1403715925584058112
1403715925634057984
1403715925684058112
1403715925734057984
1403715925784058112
1403715925834057984
1403715925884058112
1403715925934057984
1403715925984058112
1403715926034057984
1403715926084058112
1403715926134057984
1403715926184058112
1403715926234057984
1403715926284058112
1403715926334057984
1403715926384058112
1403715926434057984
1403715926484058112
1403715926534057984
1403715926584058112
1403715926634057984
1403715926684058112
1403715926734057984
1403715926784058112
1403715926834057984
1403715926884058112
1403715926934057984
1403715926984058112
1403715927034057984
1403715927084058112
1403715927134057984
1403715927184058112
1403715927234057984
1403715927284058112
1403715927334057984
1403715927384058112
1403715927434057984
1403715927484058112
1403715927534057984
1403715927584058112
1403715927634057984
1403715927684058112
1403715927734057984
1403715927784058112
1403715927834057984
1403715927884058112
1403715927934057984
1403715927984058112
1403715928034057984
1403715928084058112
1403715928134057984
1403715928184058112
1403715928234057984
1403715928284058112
1403715928334057984
1403715928384058112
1403715928434057984
1403715928484058112
1403715928534057984
1403715928584058112
1403715928634057984
1403715928684058112
1403715928734057984
1403715928784058112
1403715928834057984
1403715928884058112
1403715928934057984
1403715928984058112
1403715929034057984
1403715929084058112
1403715929134057984
1403715929184058112
1403715929234057984
1403715929284058112
1403715929334057984
1403715929384058112
1403715929434057984
1403715929484058112
1403715929534057984
1403715929584058112
1403715929634057984
1403715929684058112
1403715929734057984
1403715929784058112
1403715929834057984
1403715929884058112
1403715929934057984
1403715929984058112
1403715930034057984
1403715930084058112
1403715930134057984
1403715930184058112
1403715930234057984
1403715930284058112
1403715930334057984
1403715930384058112
1403715930434057984
1403715930484058112
1403715930534057984
1403715930584058112
1403715930634057984
1403715930684058112
1403715930734057984
1403715930784058112
1403715930834057984
1403715930884058112
1403715930934057984
1403715930984058112
1403715931034057984
1403715931084058112
1403715931134057984
1403715931184058112
1403715931234057984
1403715931284058112
1403715931334057984
1403715931384058112
1403715931434057984
1403715931484058112
1403715931534057984
1403715931584058112
1403715931634057984
1403715931684058112
1403715931734057984
1403715931784058112
1403715931834057984
1403715931884058112
1403715931934057984
1403715931984058112
1403715932034057984
1403715932084058112
1403715932134057984
1403715932184058112
1403715932234057984
1403715932284058112
1403715932334057984
1403715932384058112
1403715932434057984
1403715932484058112
1403715932534057984
1403715932584058112
1403715932634057984
1403715932684058112
1403715932734057984
1403715932784058112
1403715932834057984
1403715932884058112
1403715932934057984
1403715932984058112
1403715933034057984
1403715933084058112
1403715933134057984
1403715933184058112
1403715933234057984
1403715933284058112
1403715933334057984
1403715933384058112
1403715933434057984
1403715933484058112
1403715933534057984
1403715933584058112
1403715933634057984
1403715933684058112
1403715933734057984
1403715933784058112
1403715933834057984
1403715933884058112
1403715933934057984
1403715933984058112
1403715934034057984
1403715934084058112
1403715934134057984
1403715934184058112
1403715934234057984
1403715934284058112
1403715934334057984
1403715934384058112
1403715934434057984
1403715934484058112
1403715934534057984
1403715934584058112
1403715934634057984
1403715934684058112
1403715934734057984
1403715934784058112
1403715934834057984
1403715934884058112
1403715934934057984
1403715934984058112
1403715935034057984
1403715935084058112
1403715935134057984
1403715935184058112
1403715935234057984
1403715935284058112
1403715935334057984
1403715935384058112
1403715935434057984
1403715935484058112
1403715935534057984
1403715935584058112
1403715935634057984
1403715935684058112
1403715935734057984
1403715935784058112
1403715935834057984
1403715935884058112
1403715935934057984
1403715935984058112
1403715936034057984
1403715936084058112
1403715936134057984
1403715936184058112
1403715936234057984
1403715936284058112
1403715936334057984
1403715936384058112
1403715936434057984
1403715936484058112
1403715936534057984
1403715936584058112
1403715936634057984
1403715936684058112
1403715936734057984
1403715936784058112
1403715936834057984
1403715936884058112
1403715936934057984
1403715936984058112
1403715937034057984
1403715937084058112
1403715937134057984
1403715937184058112
1403715937234057984
1403715937284058112
1403715937334057984
1403715937384058112
1403715937434057984
1403715937484058112
1403715937534057984
1403715937584058112
1403715937634057984
1403715937684058112
1403715937734057984
1403715937784058112
1403715937834057984
1403715937884058112
1403715937934057984
1403715937984058112
1403715938034057984
1403715938084058112
1403715938134057984
1403715938184058112
1403715938234057984
1403715938284058112
1403715938334057984
1403715938384058112
1403715938434057984
1403715938484058112
1403715938534057984
1403715938584058112
1403715938634057984
1403715938684058112
1403715938734057984
1403715938784058112
1403715938834057984
1403715938884058112
1403715938934057984
1403715938984058112
1403715939034057984
1403715939084058112
1403715939134057984
1403715939184058112
1403715939234057984
1403715939284058112
1403715939334057984
1403715939384058112
1403715939434057984
1403715939484058112
1403715939534057984
1403715939584058112
1403715939634057984
1403715939684058112
1403715939734057984
1403715939784058112
1403715939834057984
1403715939884058112
1403715939934057984
1403715939984058112
1403715940034057984
1403715940084058112
1403715940134057984
1403715940184058112
1403715940234057984
1403715940284058112
1403715940334057984
1403715940384058112
1403715940434057984
1403715940484058112
1403715940534057984
1403715940584058112
1403715940634057984
1403715940684058112
1403715940734057984
1403715940784058112
1403715940834057984
1403715940884058112
1403715940934057984
1403715940984058112
1403715941034057984
1403715941084058112
1403715941134057984
1403715941184058112
1403715941234057984
1403715941284058112
1403715941334057984
1403715941384058112
1403715941434057984
1403715941484058112
1403715941534057984
1403715941584058112
1403715941634057984
1403715941684058112
1403715941734057984
1403715941784058112
1403715941834057984
1403715941884058112
1403715941934057984
1403715941984058112
1403715942034057984
1403715942084058112
1403715942134057984
1403715942184058112
1403715942234057984
1403715942284058112
1403715942334057984
1403715942384058112
1403715942434057984
1403715942484058112
1403715942534057984
1403715942584058112
1403715942634057984
1403715942684058112
1403715942734057984
1403715942784058112
1403715942834057984
1403715942884058112
1403715942934057984
1403715942984058112
1403715943034057984
1403715943084058112
1403715943134057984
1403715943184058112
1403715943234057984
1403715943284058112
1403715943334057984
1403715943384058112
1403715943434057984
1403715943484058112
1403715943534057984
1403715943584058112
1403715943634057984
1403715943684058112
1403715943734057984
1403715943784058112
1403715943834057984
1403715943884058112
1403715943934057984
1403715943984058112
1403715944034057984
1403715944084058112
1403715944134057984
1403715944184058112
1403715944234057984
1403715944284058112
1403715944334057984
1403715944384058112
1403715944434057984
1403715944484058112
1403715944534057984
1403715944584058112
1403715944634057984
1403715944684058112
1403715944734057984
1403715944784058112
1403715944834057984
1403715944884058112
1403715944934057984
1403715944984058112
1403715945034057984
1403715945084058112
1403715945134057984
1403715945184058112
1403715945234057984
1403715945284058112
1403715945334057984
1403715945384058112
1403715945434057984
1403715945484058112
1403715945534057984
1403715945584058112
1403715945634057984
1403715945684058112
1403715945734057984
1403715945784058112
1403715945834057984
1403715945884058112
1403715945934057984
1403715945984058112
1403715946034057984
1403715946084058112
1403715946134057984
1403715946184058112
1403715946234057984
1403715946284058112
1403715946334057984
1403715946384058112
1403715946434057984
1403715946484058112
1403715946534057984
1403715946584058112
1403715946634057984
1403715946684058112
1403715946734057984
1403715946784058112
1403715946834057984
1403715946884058112
1403715946934057984
1403715946984058112
1403715947034057984
1403715947084058112
1403715947134057984
1403715947184058112
1403715947234057984
1403715947284058112
1403715947334057984
1403715947384058112
1403715947434057984
1403715947484058112
1403715947534057984
1403715947584058112
1403715947634057984
1403715947684058112
1403715947734057984
1403715947784058112
1403715947834057984
1403715947884058112
1403715947934057984
1403715947984058112
1403715948034057984
1403715948084058112
1403715948134057984
1403715948184058112
1403715948234057984
1403715948284058112
1403715948334057984
1403715948384058112
1403715948434057984
1403715948484058112
1403715948534057984
1403715948584058112
1403715948634057984
1403715948684058112
1403715948734057984
1403715948784058112
1403715948834057984
1403715948884058112
1403715948934057984
1403715948984058112
1403715949034057984
1403715949084058112
1403715949134057984
1403715949184058112
1403715949234057984
1403715949284058112
1403715949334057984
1403715949384058112
1403715949434057984
1403715949484058112
1403715949534057984
1403715949584058112
1403715949634057984
1403715949684058112
1403715949734057984
1403715949784058112
1403715949834057984
1403715949884058112
1403715949934057984
1403715949984058112
1403715950034057984
1403715950084058112
1403715950134057984
1403715950184058112
1403715950234057984
1403715950284058112
1403715950334057984
1403715950384058112
1403715950434057984
1403715950484058112
1403715950534057984
1403715950584058112
1403715950634057984
1403715950684058112
1403715950734057984
1403715950784058112
1403715950834057984
1403715950884058112
1403715950934057984
1403715950984058112
1403715951034057984
1403715951084058112
1403715951134057984
1403715951184058112
1403715951234057984
1403715951284058112
1403715951334057984
1403715951384058112
1403715951434057984
1403715951484058112
1403715951534057984
1403715951584058112
1403715951634057984
1403715951684058112
1403715951734057984
1403715951784058112
1403715951834057984
1403715951884058112
1403715951934057984
1403715951984058112
1403715952034057984
1403715952084058112
1403715952134057984
1403715952184058112
1403715952234057984
1403715952284058112
1403715952334057984
1403715952384058112
1403715952434057984
1403715952484058112
1403715952534057984
1403715952584058112
1403715952634057984
1403715952684058112
1403715952734057984
1403715952784058112
1403715952834057984
1403715952884058112
1403715952934057984
1403715952984058112
1403715953034057984
1403715953084058112
1403715953134057984
1403715953184058112
1403715953234057984
1403715953284058112
1403715953334057984
1403715953384058112
1403715953434057984
1403715953484058112
1403715953534057984
1403715953584058112
1403715953634057984
1403715953684058112
1403715953734057984
1403715953784058112
1403715953834057984
1403715953884058112
1403715953934057984
1403715953984058112
1403715954034057984
1403715954084058112
1403715954134057984
1403715954184058112
1403715954234057984
1403715954284058112
1403715954334057984
1403715954384058112
1403715954434057984
1403715954484058112
1403715954534057984
1403715954584058112
1403715954634057984
1403715954684058112
1403715954734057984
1403715954784058112
1403715954834057984
1403715954884058112
1403715954934057984
1403715954984058112
1403715955034057984
1403715955084058112
1403715955134057984
1403715955184058112
1403715955234057984
1403715955284058112
1403715955334057984
1403715955384058112
1403715955434057984
1403715955484058112
1403715955534057984
1403715955584058112
1403715955634057984
1403715955684058112
1403715955734057984
1403715955784058112
1403715955834057984
1403715955884058112
1403715955934057984
1403715955984058112
1403715956034057984
1403715956084058112
1403715956134057984
1403715956184058112
1403715956234057984
1403715956284058112
1403715956334057984
1403715956384058112
1403715956434057984
1403715956484058112
1403715956534057984
1403715956584058112
1403715956634057984
1403715956684058112
1403715956734057984
1403715956784058112
1403715956834057984
1403715956884058112
1403715956934057984
1403715956984058112
1403715957034057984
1403715957084058112
1403715957134057984
1403715957184058112
1403715957234057984
1403715957284058112
1403715957334057984
1403715957384058112
1403715957434057984
1403715957484058112
1403715957534057984
1403715957584058112
1403715957634057984
1403715957684058112
1403715957734057984
1403715957784058112
1403715957834057984
1403715957884058112
1403715957934057984
1403715957984058112
1403715958034057984
1403715958084058112
1403715958134057984
1403715958184058112
1403715958234057984
1403715958284058112
1403715958334057984
1403715958384058112
1403715958434057984
1403715958484058112
1403715958534057984
1403715958584058112
1403715958634057984
1403715958684058112
1403715958734057984
1403715958784058112
1403715958834057984
1403715958884058112
1403715958934057984
1403715958984058112
1403715959034057984
1403715959084058112
1403715959134057984
1403715959184058112
1403715959234057984
1403715959284058112
1403715959334057984
1403715959384058112
1403715959434057984
1403715959484058112
1403715959534057984
1403715959584058112
1403715959634057984
1403715959684058112
1403715959734057984
1403715959784058112
1403715959834057984
1403715959884058112
1403715959934057984
1403715959984058112
1403715960034057984
1403715960084058112
1403715960134057984
1403715960184058112
1403715960234057984
1403715960284058112
1403715960334057984
1403715960384058112
1403715960434057984
1403715960484058112
1403715960534057984
1403715960584058112
1403715960634057984
1403715960684058112
1403715960734057984
1403715960784058112
1403715960834057984
1403715960884058112
1403715960934057984
1403715960984058112
1403715961034057984
1403715961084058112
1403715961134057984
1403715961184058112
1403715961234057984
1403715961284058112
1403715961334057984
1403715961384058112
1403715961434057984
1403715961484058112
1403715961534057984
1403715961584058112
1403715961634057984
1403715961684058112
1403715961734057984
1403715961784058112
1403715961834057984
1403715961884058112
1403715961934057984
1403715961984058112
1403715962034057984
1403715962084058112
1403715962134057984
1403715962184058112
1403715962234057984
1403715962284058112
1403715962334057984
1403715962384058112
1403715962434057984
1403715962484058112
1403715962534057984
1403715962584058112
1403715962634057984
1403715962684058112
1403715962734057984
1403715962784058112
1403715962834057984
1403715962884058112
1403715962934057984
1403715962984058112
1403715963034057984
1403715963084058112
1403715963134057984
1403715963184058112
1403715963234057984
1403715963284058112
1403715963334057984
1403715963384058112
1403715963434057984
1403715963484058112
1403715963534057984
1403715963584058112
1403715963634057984
1403715963684058112
1403715963734057984
1403715963784058112
1403715963834057984
1403715963884058112
1403715963934057984
1403715963984058112
1403715964034057984
1403715964084058112
1403715964134057984
1403715964184058112
1403715964234057984
1403715964284058112
1403715964334057984
1403715964384058112
1403715964434057984
1403715964484058112
1403715964534057984
1403715964584058112
1403715964634057984
1403715964684058112
1403715964734057984
1403715964784058112
1403715964834057984
1403715964884058112
1403715964934057984
1403715964984058112
1403715965034057984
1403715965084058112
1403715965134057984
1403715965184058112
1403715965234057984
1403715965284058112
1403715965334057984
1403715965384058112
1403715965434057984
1403715965484058112
1403715965534057984
1403715965584058112
1403715965634057984
1403715965684058112
1403715965734057984
1403715965784058112
1403715965834057984
1403715965884058112
1403715965934057984
1403715965984058112
1403715966034057984
1403715966084058112
1403715966134057984
1403715966184058112
1403715966234057984
1403715966284058112
1403715966334057984
1403715966384058112
1403715966434057984
1403715966484058112
1403715966534057984
1403715966584058112
1403715966634057984
1403715966684058112
1403715966734057984
1403715966784058112
1403715966834057984
1403715966884058112
1403715966934057984
1403715966984058112
1403715967034057984
1403715967084058112
1403715967134057984
1403715967184058112
1403715967234057984
1403715967284058112
1403715967334057984
1403715967384058112
1403715967434057984
1403715967484058112
1403715967534057984
1403715967584058112
1403715967634057984
1403715967684058112
1403715967734057984
1403715967784058112
1403715967834057984
1403715967884058112
1403715967934057984
1403715967984058112
1403715968034057984
1403715968084058112
1403715968134057984
1403715968184058112
1403715968234057984
1403715968284058112
1403715968334057984
1403715968384058112
1403715968434057984
1403715968484058112
1403715968534057984
1403715968584058112
1403715968634057984
1403715968684058112
1403715968734057984
1403715968784058112
1403715968834057984
1403715968884058112
1403715968934057984
1403715968984058112
1403715969034057984
1403715969084058112
1403715969134057984
1403715969184058112
1403715969234057984
1403715969284058112
1403715969334057984
1403715969384058112
1403715969434057984
1403715969484058112
1403715969534057984
1403715969584058112
1403715969634057984
1403715969684058112
1403715969734057984
1403715969784058112
1403715969834057984
1403715969884058112
1403715969934057984
1403715969984058112
1403715970034057984
1403715970084058112
1403715970134057984
1403715970184058112
1403715970234057984
1403715970284058112
1403715970334057984
1403715970384058112
1403715970434057984
1403715970484058112
1403715970534057984
1403715970584058112
1403715970634057984
1403715970684058112
1403715970734057984
1403715970784058112
1403715970834057984
1403715970884058112
1403715970934057984
1403715970984058112
1403715971034057984
1403715971084058112
1403715971134057984
1403715971184058112
1403715971234057984
1403715971284058112
1403715971334057984
1403715971384058112
1403715971434057984
1403715971484058112
1403715971534057984
1403715971584058112
1403715971634057984
1403715971684058112
1403715971734057984
1403715971784058112
1403715971834057984
1403715971884058112
1403715971934057984
1403715971984058112
1403715972034057984
1403715972084058112
1403715972134057984
1403715972184058112
1403715972234057984
1403715972284058112
1403715972334057984
1403715972384058112
1403715972434057984
1403715972484058112
1403715972534057984
1403715972584058112
1403715972634057984
1403715972684058112
1403715972734057984
1403715972784058112
1403715972834057984
1403715972884058112
1403715972934057984
1403715972984058112
1403715973034057984
1403715973084058112
1403715973134057984
1403715973184058112
1403715973234057984
1403715973284058112
1403715973334057984
1403715973384058112
1403715973434057984
1403715973484058112
1403715973534057984
1403715973584058112
1403715973634057984
1403715973684058112
1403715973734057984
1403715973784058112
1403715973834057984
1403715973884058112
1403715973934057984
1403715973984058112
1403715974034057984
1403715974084058112
1403715974134057984
1403715974184058112
1403715974234057984
1403715974284058112
1403715974334057984
1403715974384058112
1403715974434057984
1403715974484058112
1403715974534057984
1403715974584058112
1403715974634057984
1403715974684058112
1403715974734057984
1403715974784058112
1403715974834057984
1403715974884058112
1403715974934057984
1403715974984058112
1403715975034057984
1403715975084058112
1403715975134057984
1403715975184058112
1403715975234057984
1403715975284058112
1403715975334057984
1403715975384058112
1403715975434057984
1403715975484058112
1403715975534057984
1403715975584058112
1403715975634057984
1403715975684058112
1403715975734057984
1403715975784058112
1403715975834057984
1403715975884058112
1403715975934057984
1403715975984058112
1403715976034057984
1403715976084058112
1403715976134057984
1403715976184058112
1403715976234057984
1403715976284058112
1403715976334057984
1403715976384058112
1403715976434057984
1403715976484058112
1403715976534057984
1403715976584058112
1403715976634057984
1403715976684058112
1403715976734057984
1403715976784058112
1403715976834057984
1403715976884058112
1403715976934057984
1403715976984058112
1403715977034057984
1403715977084058112
1403715977134057984
1403715977184058112
1403715977234057984
1403715977284058112
1403715977334057984
1403715977384058112
1403715977434057984
1403715977484058112
1403715977534057984
1403715977584058112
1403715977634057984
1403715977684058112
1403715977734057984
1403715977784058112
1403715977834057984
1403715977884058112
1403715977934057984
1403715977984058112
1403715978034057984
1403715978084058112
1403715978134057984
1403715978184058112
1403715978234057984
1403715978284058112
1403715978334057984
1403715978384058112
1403715978434057984
1403715978484058112
1403715978534057984
1403715978584058112
1403715978634057984
1403715978684058112
1403715978734057984
1403715978784058112
1403715978834057984
1403715978884058112
1403715978934057984
1403715978984058112
1403715979034057984
1403715979084058112
1403715979134057984
1403715979184058112
1403715979234057984
1403715979284058112
1403715979334057984
1403715979384058112
1403715979434057984
1403715979484058112
1403715979534057984
1403715979584058112
1403715979634057984
1403715979684058112
1403715979734057984
1403715979784058112
1403715979834057984
1403715979884058112
1403715979934057984
1403715979984058112
1403715980034057984
1403715980084058112
1403715980134057984
1403715980184058112
1403715980234057984
1403715980284058112
1403715980334057984
1403715980384058112
1403715980434057984
1403715980484058112
1403715980534057984
1403715980584058112
1403715980634057984
1403715980684058112
1403715980734057984
1403715980784058112
1403715980834057984
1403715980884058112
1403715980934057984
1403715980984058112
1403715981034057984
1403715981084058112
1403715981134057984
1403715981184058112
1403715981234057984
1403715981284058112
1403715981334057984
1403715981384058112
1403715981434057984
1403715981484058112
1403715981534057984
1403715981584058112
1403715981634057984
1403715981684058112
1403715981734057984
1403715981784058112
1403715981834057984
1403715981884058112
1403715981934057984
1403715981984058112
1403715982034057984
1403715982084058112
1403715982134057984
1403715982184058112
1403715982234057984
1403715982284058112
1403715982334057984
1403715982384058112
1403715982434057984
1403715982484058112
1403715982534057984
1403715982584058112
1403715982634057984
1403715982684058112
1403715982734057984
1403715982784058112
1403715982834057984
1403715982884058112
1403715982934057984
1403715982984058112
1403715983034057984
1403715983084058112
1403715983134057984
1403715983184058112
1403715983234057984
1403715983284058112
1403715983334057984
1403715983384058112
1403715983434057984
1403715983484058112
1403715983534057984
1403715983584058112
1403715983634057984
1403715983684058112
1403715983734057984
1403715983784058112
1403715983834057984
1403715983884058112
1403715983934057984
1403715983984058112
1403715984034057984
1403715984084058112
1403715984134057984
1403715984184058112
1403715984234057984
1403715984284058112
1403715984334057984
1403715984384058112
1403715984434057984
1403715984484058112
1403715984534057984
1403715984584058112
1403715984634057984
1403715984684058112
1403715984734057984
1403715984784058112
1403715984834057984
1403715984884058112
1403715984934057984
1403715984984058112
1403715985034057984
1403715985084058112
1403715985134057984
1403715985184058112
1403715985234057984
1403715985284058112
1403715985334057984
1403715985384058112
1403715985434057984
1403715985484058112
1403715985534057984
1403715985584058112
1403715985634057984
1403715985684058112
1403715985734057984
1403715985784058112
1403715985834057984
1403715985884058112
1403715985934057984
1403715985984058112
1403715986034057984
1403715986084058112
1403715986134057984
1403715986184058112
1403715986234057984
1403715986284058112
1403715986334057984
1403715986384058112
1403715986434057984
1403715986484058112
1403715986534057984
1403715986584058112
1403715986634057984
1403715986684058112
1403715986734057984
1403715986784058112
1403715986834057984
1403715986884058112
1403715986934057984
1403715986984058112
1403715987034057984
1403715987084058112
1403715987134057984
1403715987184058112
1403715987234057984
1403715987284058112
1403715987334057984
1403715987384058112
1403715987434057984
1403715987484058112
1403715987534057984
1403715987584058112
1403715987634057984
1403715987684058112
1403715987734057984
1403715987784058112
1403715987834057984
1403715987884058112
1403715987934057984
1403715987984058112
1403715988034057984
1403715988084058112
1403715988134057984
1403715988184058112
1403715988234057984
1403715988284058112
1403715988334057984
1403715988384058112
1403715988434057984
1403715988484058112
1403715988534057984
1403715988584058112
1403715988634057984
1403715988684058112
1403715988734057984
1403715988784058112
1403715988834057984
1403715988884058112
1403715988934057984
1403715988984058112
1403715989034057984
1403715989084058112
1403715989134057984
1403715989184058112
1403715989234057984
1403715989284058112
1403715989334057984
1403715989384058112
1403715989434057984
1403715989484058112
1403715989534057984
1403715989584058112
1403715989634057984
1403715989684058112
1403715989734057984
1403715989784058112
1403715989834057984
1403715989884058112
1403715989934057984
1403715989984058112
1403715990034057984
1403715990084058112
1403715990134057984
1403715990184058112
1403715990234057984
1403715990284058112
1403715990334057984
1403715990384058112
1403715990434057984
1403715990484058112
1403715990534057984
1403715990584058112
1403715990634057984
1403715990684058112
1403715990734057984
1403715990784058112
1403715990834057984
1403715990884058112
1403715990934057984
1403715990984058112
1403715991034057984
1403715991084058112
1403715991134057984
1403715991184058112
1403715991234057984
1403715991284058112
1403715991334057984
1403715991384058112
1403715991434057984
1403715991484058112
1403715991534057984
1403715991584058112
1403715991634057984
1403715991684058112
1403715991734057984
1403715991784058112
1403715991834057984
1403715991884058112
1403715991934057984
1403715991984058112
1403715992034057984
1403715992084058112
1403715992134057984
1403715992184058112
1403715992234057984
1403715992284058112
1403715992334057984
1403715992384058112
1403715992434057984
1403715992484058112
1403715992534057984
1403715992584058112
1403715992634057984
1403715992684058112
1403715992734057984
1403715992784058112
1403715992834057984
1403715992884058112
1403715992934057984
1403715992984058112
1403715993034057984
1403715993084058112
1403715993134057984
1403715993184058112
1403715993234057984
1403715993284058112
1403715993334057984
1403715993384058112
1403715993434057984
1403715993484058112
1403715993534057984
1403715993584058112
1403715993634057984
1403715993684058112
1403715993734057984
1403715993784058112
1403715993834057984
1403715993884058112
1403715993934057984
1403715993984058112
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/V201.txt
================================================
1413393212255760384
1413393212305760512
1413393212355760384
1413393212405760512
1413393212455760384
1413393212505760512
1413393212555760384
1413393212605760512
1413393212655760384
1413393212705760512
1413393212755760384
1413393212805760512
1413393212855760384
1413393212905760512
1413393212955760384
1413393213005760512
1413393213055760384
1413393213105760512
1413393213155760384
1413393213205760512
1413393213255760384
1413393213305760512
1413393213355760384
1413393213405760512
1413393213455760384
1413393213505760512
1413393213555760384
1413393213605760512
1413393213655760384
1413393213705760512
1413393213755760384
1413393213805760512
1413393213855760384
1413393213905760512
1413393213955760384
1413393214005760512
1413393214055760384
1413393214105760512
1413393214155760384
1413393214205760512
1413393214255760384
1413393214305760512
1413393214355760384
1413393214405760512
1413393214455760384
1413393214505760512
1413393214555760384
1413393214605760512
1413393214655760384
1413393214705760512
1413393214755760384
1413393214805760512
1413393214855760384
1413393214905760512
1413393214955760384
1413393215005760512
1413393215055760384
1413393215105760512
1413393215155760384
1413393215205760512
1413393215255760384
1413393215305760512
1413393215355760384
1413393215405760512
1413393215455760384
1413393215505760512
1413393215555760384
1413393215605760512
1413393215655760384
1413393215705760512
1413393215755760384
1413393215805760512
1413393215855760384
1413393215905760512
1413393215955760384
1413393216005760512
1413393216055760384
1413393216105760512
1413393216155760384
1413393216205760512
1413393216255760384
1413393216305760512
1413393216355760384
1413393216405760512
1413393216455760384
1413393216505760512
1413393216555760384
1413393216605760512
1413393216655760384
1413393216705760512
1413393216755760384
1413393216805760512
1413393216855760384
1413393216905760512
1413393216955760384
1413393217005760512
1413393217055760384
1413393217105760512
1413393217155760384
1413393217205760512
1413393217255760384
1413393217305760512
1413393217355760384
1413393217405760512
1413393217455760384
1413393217505760512
1413393217555760384
1413393217605760512
1413393217655760384
1413393217705760512
1413393217755760384
1413393217805760512
1413393217855760384
1413393217905760512
1413393217955760384
1413393218005760512
1413393218055760384
1413393218105760512
1413393218155760384
1413393218205760512
1413393218255760384
1413393218305760512
1413393218355760384
1413393218405760512
1413393218455760384
1413393218505760512
1413393218555760384
1413393218605760512
1413393218655760384
1413393218705760512
1413393218755760384
1413393218805760512
1413393218855760384
1413393218905760512
1413393218955760384
1413393219005760512
1413393219055760384
1413393219105760512
1413393219155760384
1413393219205760512
1413393219255760384
1413393219305760512
1413393219355760384
1413393219405760512
1413393219455760384
1413393219505760512
1413393219555760384
1413393219605760512
1413393219655760384
1413393219705760512
1413393219755760384
1413393219805760512
1413393219855760384
1413393219905760512
1413393219955760384
1413393220005760512
1413393220055760384
1413393220105760512
1413393220155760384
1413393220205760512
1413393220255760384
1413393220305760512
1413393220355760384
1413393220405760512
1413393220455760384
1413393220505760512
1413393220555760384
1413393220605760512
1413393220655760384
1413393220705760512
1413393220755760384
1413393220805760512
1413393220855760384
1413393220905760512
1413393220955760384
1413393221005760512
1413393221055760384
1413393221105760512
1413393221155760384
1413393221205760512
1413393221255760384
1413393221305760512
1413393221355760384
1413393221405760512
1413393221455760384
1413393221505760512
1413393221555760384
1413393221605760512
1413393221655760384
1413393221705760512
1413393221755760384
1413393221805760512
1413393221855760384
1413393221905760512
1413393221955760384
1413393222005760512
1413393222055760384
1413393222105760512
1413393222155760384
1413393222205760512
1413393222255760384
1413393222305760512
1413393222355760384
1413393222405760512
1413393222455760384
1413393222505760512
1413393222555760384
1413393222605760512
1413393222655760384
1413393222705760512
1413393222755760384
1413393222805760512
1413393222855760384
1413393222905760512
1413393222955760384
1413393223005760512
1413393223055760384
1413393223105760512
1413393223155760384
1413393223205760512
1413393223255760384
1413393223305760512
1413393223355760384
1413393223405760512
1413393223455760384
1413393223505760512
1413393223555760384
1413393223605760512
1413393223655760384
1413393223705760512
1413393223755760384
1413393223805760512
1413393223855760384
1413393223905760512
1413393223955760384
1413393224005760512
1413393224055760384
1413393224105760512
1413393224155760384
1413393224205760512
1413393224255760384
1413393224305760512
1413393224355760384
1413393224405760512
1413393224455760384
1413393224505760512
1413393224555760384
1413393224605760512
1413393224655760384
1413393224705760512
1413393224755760384
1413393224805760512
1413393224855760384
1413393224905760512
1413393224955760384
1413393225005760512
1413393225055760384
1413393225105760512
1413393225155760384
1413393225205760512
1413393225255760384
1413393225305760512
1413393225355760384
1413393225405760512
1413393225455760384
1413393225505760512
1413393225555760384
1413393225605760512
1413393225655760384
1413393225705760512
1413393225755760384
1413393225805760512
1413393225855760384
1413393225905760512
1413393225955760384
1413393226005760512
1413393226055760384
1413393226105760512
1413393226155760384
1413393226205760512
1413393226255760384
1413393226305760512
1413393226355760384
1413393226405760512
1413393226455760384
1413393226505760512
1413393226555760384
1413393226605760512
1413393226655760384
1413393226705760512
1413393226755760384
1413393226805760512
1413393226855760384
1413393226905760512
1413393226955760384
1413393227005760512
1413393227055760384
1413393227105760512
1413393227155760384
1413393227205760512
1413393227255760384
1413393227305760512
1413393227355760384
1413393227405760512
1413393227455760384
1413393227505760512
1413393227555760384
1413393227605760512
1413393227655760384
1413393227705760512
1413393227755760384
1413393227805760512
1413393227855760384
1413393227905760512
1413393227955760384
1413393228005760512
1413393228055760384
1413393228105760512
1413393228155760384
1413393228205760512
1413393228255760384
1413393228305760512
1413393228355760384
1413393228405760512
1413393228455760384
1413393228505760512
1413393228555760384
1413393228605760512
1413393228655760384
1413393228705760512
1413393228755760384
1413393228805760512
1413393228855760384
1413393228905760512
1413393228955760384
1413393229005760512
1413393229055760384
1413393229105760512
1413393229155760384
1413393229205760512
1413393229255760384
1413393229305760512
1413393229355760384
1413393229405760512
1413393229455760384
1413393229505760512
1413393229555760384
1413393229605760512
1413393229655760384
1413393229705760512
1413393229755760384
1413393229805760512
1413393229855760384
1413393229905760512
1413393229955760384
1413393230005760512
1413393230055760384
1413393230105760512
1413393230155760384
1413393230205760512
1413393230255760384
1413393230305760512
1413393230355760384
1413393230405760512
1413393230455760384
1413393230505760512
1413393230555760384
1413393230605760512
1413393230655760384
1413393230705760512
1413393230755760384
1413393230805760512
1413393230855760384
1413393230905760512
1413393230955760384
1413393231005760512
1413393231055760384
1413393231105760512
1413393231155760384
1413393231205760512
1413393231255760384
1413393231305760512
1413393231355760384
1413393231405760512
1413393231455760384
1413393231505760512
1413393231555760384
1413393231605760512
1413393231655760384
1413393231705760512
1413393231755760384
1413393231805760512
1413393231855760384
1413393231905760512
1413393231955760384
1413393232005760512
1413393232055760384
1413393232105760512
1413393232155760384
1413393232205760512
1413393232255760384
1413393232305760512
1413393232355760384
1413393232405760512
1413393232455760384
1413393232505760512
1413393232555760384
1413393232605760512
1413393232655760384
1413393232705760512
1413393232755760384
1413393232805760512
1413393232855760384
1413393232905760512
1413393232955760384
1413393233005760512
1413393233055760384
1413393233105760512
1413393233155760384
1413393233205760512
1413393233255760384
1413393233305760512
1413393233355760384
1413393233405760512
1413393233455760384
1413393233505760512
1413393233555760384
1413393233605760512
1413393233655760384
1413393233705760512
1413393233755760384
1413393233805760512
1413393233855760384
1413393233905760512
1413393233955760384
1413393234005760512
1413393234055760384
1413393234105760512
1413393234155760384
1413393234205760512
1413393234255760384
1413393234305760512
1413393234355760384
1413393234405760512
1413393234455760384
1413393234505760512
1413393234555760384
1413393234605760512
1413393234655760384
1413393234705760512
1413393234755760384
1413393234805760512
1413393234855760384
1413393234905760512
1413393234955760384
1413393235005760512
1413393235055760384
1413393235105760512
1413393235155760384
1413393235205760512
1413393235255760384
1413393235305760512
1413393235355760384
1413393235405760512
1413393235455760384
1413393235505760512
1413393235555760384
1413393235605760512
1413393235655760384
1413393235705760512
1413393235755760384
1413393235805760512
1413393235855760384
1413393235905760512
1413393235955760384
1413393236005760512
1413393236055760384
1413393236105760512
1413393236155760384
1413393236205760512
1413393236255760384
1413393236305760512
1413393236355760384
1413393236405760512
1413393236455760384
1413393236505760512
1413393236555760384
1413393236605760512
1413393236655760384
1413393236705760512
1413393236755760384
1413393236805760512
1413393236855760384
1413393236905760512
1413393236955760384
1413393237005760512
1413393237055760384
1413393237105760512
1413393237155760384
1413393237205760512
1413393237255760384
1413393237305760512
1413393237355760384
1413393237405760512
1413393237455760384
1413393237505760512
1413393237555760384
1413393237605760512
1413393237655760384
1413393237705760512
1413393237755760384
1413393237805760512
1413393237855760384
1413393237905760512
1413393237955760384
1413393238005760512
1413393238055760384
1413393238105760512
1413393238155760384
1413393238205760512
1413393238255760384
1413393238305760512
1413393238355760384
1413393238405760512
1413393238455760384
1413393238505760512
1413393238555760384
1413393238605760512
1413393238655760384
1413393238705760512
1413393238755760384
1413393238805760512
1413393238855760384
1413393238905760512
1413393238955760384
1413393239005760512
1413393239055760384
1413393239105760512
1413393239155760384
1413393239205760512
1413393239255760384
1413393239305760512
1413393239355760384
1413393239405760512
1413393239455760384
1413393239505760512
1413393239555760384
1413393239605760512
1413393239655760384
1413393239705760512
1413393239755760384
1413393239805760512
1413393239855760384
1413393239905760512
1413393239955760384
1413393240005760512
1413393240055760384
1413393240105760512
1413393240155760384
1413393240205760512
1413393240255760384
1413393240305760512
1413393240355760384
1413393240405760512
1413393240455760384
1413393240505760512
1413393240555760384
1413393240605760512
1413393240655760384
1413393240705760512
1413393240755760384
1413393240805760512
1413393240855760384
1413393240905760512
1413393240955760384
1413393241005760512
1413393241055760384
1413393241105760512
1413393241155760384
1413393241205760512
1413393241255760384
1413393241305760512
1413393241355760384
1413393241405760512
1413393241455760384
1413393241505760512
1413393241555760384
1413393241605760512
1413393241655760384
1413393241705760512
1413393241755760384
1413393241805760512
1413393241855760384
1413393241905760512
1413393241955760384
1413393242005760512
1413393242055760384
1413393242105760512
1413393242155760384
1413393242205760512
1413393242255760384
1413393242305760512
1413393242355760384
1413393242405760512
1413393242455760384
1413393242505760512
1413393242555760384
1413393242605760512
1413393242655760384
1413393242705760512
1413393242755760384
1413393242805760512
1413393242855760384
1413393242905760512
1413393242955760384
1413393243005760512
1413393243055760384
1413393243105760512
1413393243155760384
1413393243205760512
1413393243255760384
1413393243305760512
1413393243355760384
1413393243405760512
1413393243455760384
1413393243505760512
1413393243555760384
1413393243605760512
1413393243655760384
1413393243705760512
1413393243755760384
1413393243805760512
1413393243855760384
1413393243905760512
1413393243955760384
1413393244005760512
1413393244055760384
1413393244105760512
1413393244155760384
1413393244205760512
1413393244255760384
1413393244305760512
1413393244355760384
1413393244405760512
1413393244455760384
1413393244505760512
1413393244555760384
1413393244605760512
1413393244655760384
1413393244705760512
1413393244755760384
1413393244805760512
1413393244855760384
1413393244905760512
1413393244955760384
1413393245005760512
1413393245055760384
1413393245105760512
1413393245155760384
1413393245205760512
1413393245255760384
1413393245305760512
1413393245355760384
1413393245405760512
1413393245455760384
1413393245505760512
1413393245555760384
1413393245605760512
1413393245655760384
1413393245705760512
1413393245755760384
1413393245805760512
1413393245855760384
1413393245905760512
1413393245955760384
1413393246005760512
1413393246055760384
1413393246105760512
1413393246155760384
1413393246205760512
1413393246255760384
1413393246305760512
1413393246355760384
1413393246405760512
1413393246455760384
1413393246505760512
1413393246555760384
1413393246605760512
1413393246655760384
1413393246705760512
1413393246755760384
1413393246805760512
1413393246855760384
1413393246905760512
1413393246955760384
1413393247005760512
1413393247055760384
1413393247105760512
1413393247155760384
1413393247205760512
1413393247255760384
1413393247305760512
1413393247355760384
1413393247405760512
1413393247455760384
1413393247505760512
1413393247555760384
1413393247605760512
1413393247655760384
1413393247705760512
1413393247755760384
1413393247805760512
1413393247855760384
1413393247905760512
1413393247955760384
1413393248005760512
1413393248055760384
1413393248105760512
1413393248155760384
1413393248205760512
1413393248255760384
1413393248305760512
1413393248355760384
1413393248405760512
1413393248455760384
1413393248505760512
1413393248555760384
1413393248605760512
1413393248655760384
1413393248705760512
1413393248755760384
1413393248805760512
1413393248855760384
1413393248905760512
1413393248955760384
1413393249005760512
1413393249055760384
1413393249105760512
1413393249155760384
1413393249205760512
1413393249255760384
1413393249305760512
1413393249355760384
1413393249405760512
1413393249455760384
1413393249505760512
1413393249555760384
1413393249605760512
1413393249655760384
1413393249705760512
1413393249755760384
1413393249805760512
1413393249855760384
1413393249905760512
1413393249955760384
1413393250005760512
1413393250055760384
1413393250105760512
1413393250155760384
1413393250205760512
1413393250255760384
1413393250305760512
1413393250355760384
1413393250405760512
1413393250455760384
1413393250505760512
1413393250555760384
1413393250605760512
1413393250655760384
1413393250705760512
1413393250755760384
1413393250805760512
1413393250855760384
1413393250905760512
1413393250955760384
1413393251005760512
1413393251055760384
1413393251105760512
1413393251155760384
1413393251205760512
1413393251255760384
1413393251305760512
1413393251355760384
1413393251405760512
1413393251455760384
1413393251505760512
1413393251555760384
1413393251605760512
1413393251655760384
1413393251705760512
1413393251755760384
1413393251805760512
1413393251855760384
1413393251905760512
1413393251955760384
1413393252005760512
1413393252055760384
1413393252105760512
1413393252155760384
1413393252205760512
1413393252255760384
1413393252305760512
1413393252355760384
1413393252405760512
1413393252455760384
1413393252505760512
1413393252555760384
1413393252605760512
1413393252655760384
1413393252705760512
1413393252755760384
1413393252805760512
1413393252855760384
1413393252905760512
1413393252955760384
1413393253005760512
1413393253055760384
1413393253105760512
1413393253155760384
1413393253205760512
1413393253255760384
1413393253305760512
1413393253355760384
1413393253405760512
1413393253455760384
1413393253505760512
1413393253555760384
1413393253605760512
1413393253655760384
1413393253705760512
1413393253755760384
1413393253805760512
1413393253855760384
1413393253905760512
1413393253955760384
1413393254005760512
1413393254055760384
1413393254105760512
1413393254155760384
1413393254205760512
1413393254255760384
1413393254305760512
1413393254355760384
1413393254405760512
1413393254455760384
1413393254505760512
1413393254555760384
1413393254605760512
1413393254655760384
1413393254705760512
1413393254755760384
1413393254805760512
1413393254855760384
1413393254905760512
1413393254955760384
1413393255005760512
1413393255055760384
1413393255105760512
1413393255155760384
1413393255205760512
1413393255255760384
1413393255305760512
1413393255355760384
1413393255405760512
1413393255455760384
1413393255505760512
1413393255555760384
1413393255605760512
1413393255655760384
1413393255705760512
1413393255755760384
1413393255805760512
1413393255855760384
1413393255905760512
1413393255955760384
1413393256005760512
1413393256055760384
1413393256105760512
1413393256155760384
1413393256205760512
1413393256255760384
1413393256305760512
1413393256355760384
1413393256405760512
1413393256455760384
1413393256505760512
1413393256555760384
1413393256605760512
1413393256655760384
1413393256705760512
1413393256755760384
1413393256805760512
1413393256855760384
1413393256905760512
1413393256955760384
1413393257005760512
1413393257055760384
1413393257105760512
1413393257155760384
1413393257205760512
1413393257255760384
1413393257305760512
1413393257355760384
1413393257405760512
1413393257455760384
1413393257505760512
1413393257555760384
1413393257605760512
1413393257655760384
1413393257705760512
1413393257755760384
1413393257805760512
1413393257855760384
1413393257905760512
1413393257955760384
1413393258005760512
1413393258055760384
1413393258105760512
1413393258155760384
1413393258205760512
1413393258255760384
1413393258305760512
1413393258355760384
1413393258405760512
1413393258455760384
1413393258505760512
1413393258555760384
1413393258605760512
1413393258655760384
1413393258705760512
1413393258755760384
1413393258805760512
1413393258855760384
1413393258905760512
1413393258955760384
1413393259005760512
1413393259055760384
1413393259105760512
1413393259155760384
1413393259205760512
1413393259255760384
1413393259305760512
1413393259355760384
1413393259405760512
1413393259455760384
1413393259505760512
1413393259555760384
1413393259605760512
1413393259655760384
1413393259705760512
1413393259755760384
1413393259805760512
1413393259855760384
1413393259905760512
1413393259955760384
1413393260005760512
1413393260055760384
1413393260105760512
1413393260155760384
1413393260205760512
1413393260255760384
1413393260305760512
1413393260355760384
1413393260405760512
1413393260455760384
1413393260505760512
1413393260555760384
1413393260605760512
1413393260655760384
1413393260705760512
1413393260755760384
1413393260805760512
1413393260855760384
1413393260905760512
1413393260955760384
1413393261005760512
1413393261055760384
1413393261105760512
1413393261155760384
1413393261205760512
1413393261255760384
1413393261305760512
1413393261355760384
1413393261405760512
1413393261455760384
1413393261505760512
1413393261555760384
1413393261605760512
1413393261655760384
1413393261705760512
1413393261755760384
1413393261805760512
1413393261855760384
1413393261905760512
1413393261955760384
1413393262005760512
1413393262055760384
1413393262105760512
1413393262155760384
1413393262205760512
1413393262255760384
1413393262305760512
1413393262355760384
1413393262405760512
1413393262455760384
1413393262505760512
1413393262555760384
1413393262605760512
1413393262655760384
1413393262705760512
1413393262755760384
1413393262805760512
1413393262855760384
1413393262905760512
1413393262955760384
1413393263005760512
1413393263055760384
1413393263105760512
1413393263155760384
1413393263205760512
1413393263255760384
1413393263305760512
1413393263355760384
1413393263405760512
1413393263455760384
1413393263505760512
1413393263555760384
1413393263605760512
1413393263655760384
1413393263705760512
1413393263755760384
1413393263805760512
1413393263855760384
1413393263905760512
1413393263955760384
1413393264005760512
1413393264055760384
1413393264105760512
1413393264155760384
1413393264205760512
1413393264255760384
1413393264305760512
1413393264355760384
1413393264405760512
1413393264455760384
1413393264505760512
1413393264555760384
1413393264605760512
1413393264655760384
1413393264705760512
1413393264755760384
1413393264805760512
1413393264855760384
1413393264905760512
1413393264955760384
1413393265005760512
1413393265055760384
1413393265105760512
1413393265155760384
1413393265205760512
1413393265255760384
1413393265305760512
1413393265355760384
1413393265405760512
1413393265455760384
1413393265505760512
1413393265555760384
1413393265605760512
1413393265655760384
1413393265705760512
1413393265755760384
1413393265805760512
1413393265855760384
1413393265905760512
1413393265955760384
1413393266005760512
1413393266055760384
1413393266105760512
1413393266155760384
1413393266205760512
1413393266255760384
1413393266305760512
1413393266355760384
1413393266405760512
1413393266455760384
1413393266505760512
1413393266555760384
1413393266605760512
1413393266655760384
1413393266705760512
1413393266755760384
1413393266805760512
1413393266855760384
1413393266905760512
1413393266955760384
1413393267005760512
1413393267055760384
1413393267105760512
1413393267155760384
1413393267205760512
1413393267255760384
1413393267305760512
1413393267355760384
1413393267405760512
1413393267455760384
1413393267505760512
1413393267555760384
1413393267605760512
1413393267655760384
1413393267705760512
1413393267755760384
1413393267805760512
1413393267855760384
1413393267905760512
1413393267955760384
1413393268005760512
1413393268055760384
1413393268105760512
1413393268155760384
1413393268205760512
1413393268255760384
1413393268305760512
1413393268355760384
1413393268405760512
1413393268455760384
1413393268505760512
1413393268555760384
1413393268605760512
1413393268655760384
1413393268705760512
1413393268755760384
1413393268805760512
1413393268855760384
1413393268905760512
1413393268955760384
1413393269005760512
1413393269055760384
1413393269105760512
1413393269155760384
1413393269205760512
1413393269255760384
1413393269305760512
1413393269355760384
1413393269405760512
1413393269455760384
1413393269505760512
1413393269555760384
1413393269605760512
1413393269655760384
1413393269705760512
1413393269755760384
1413393269805760512
1413393269855760384
1413393269905760512
1413393269955760384
1413393270005760512
1413393270055760384
1413393270105760512
1413393270155760384
1413393270205760512
1413393270255760384
1413393270305760512
1413393270355760384
1413393270405760512
1413393270455760384
1413393270505760512
1413393270555760384
1413393270605760512
1413393270655760384
1413393270705760512
1413393270755760384
1413393270805760512
1413393270855760384
1413393270905760512
1413393270955760384
1413393271005760512
1413393271055760384
1413393271105760512
1413393271155760384
1413393271205760512
1413393271255760384
1413393271305760512
1413393271355760384
1413393271405760512
1413393271455760384
1413393271505760512
1413393271555760384
1413393271605760512
1413393271655760384
1413393271705760512
1413393271755760384
1413393271805760512
1413393271855760384
1413393271905760512
1413393271955760384
1413393272005760512
1413393272055760384
1413393272105760512
1413393272155760384
1413393272205760512
1413393272255760384
1413393272305760512
1413393272355760384
1413393272405760512
1413393272455760384
1413393272505760512
1413393272555760384
1413393272605760512
1413393272655760384
1413393272705760512
1413393272755760384
1413393272805760512
1413393272855760384
1413393272905760512
1413393272955760384
1413393273005760512
1413393273055760384
1413393273105760512
1413393273155760384
1413393273205760512
1413393273255760384
1413393273305760512
1413393273355760384
1413393273405760512
1413393273455760384
1413393273505760512
1413393273555760384
1413393273605760512
1413393273655760384
1413393273705760512
1413393273755760384
1413393273805760512
1413393273855760384
1413393273905760512
1413393273955760384
1413393274005760512
1413393274055760384
1413393274105760512
1413393274155760384
1413393274205760512
1413393274255760384
1413393274305760512
1413393274355760384
1413393274405760512
1413393274455760384
1413393274505760512
1413393274555760384
1413393274605760512
1413393274655760384
1413393274705760512
1413393274755760384
1413393274805760512
1413393274855760384
1413393274905760512
1413393274955760384
1413393275005760512
1413393275055760384
1413393275105760512
1413393275155760384
1413393275205760512
1413393275255760384
1413393275305760512
1413393275355760384
1413393275405760512
1413393275455760384
1413393275505760512
1413393275555760384
1413393275605760512
1413393275655760384
1413393275705760512
1413393275755760384
1413393275805760512
1413393275855760384
1413393275905760512
1413393275955760384
1413393276005760512
1413393276055760384
1413393276105760512
1413393276155760384
1413393276205760512
1413393276255760384
1413393276305760512
1413393276355760384
1413393276405760512
1413393276455760384
1413393276505760512
1413393276555760384
1413393276605760512
1413393276655760384
1413393276705760512
1413393276755760384
1413393276805760512
1413393276855760384
1413393276905760512
1413393276955760384
1413393277005760512
1413393277055760384
1413393277105760512
1413393277155760384
1413393277205760512
1413393277255760384
1413393277305760512
1413393277355760384
1413393277405760512
1413393277455760384
1413393277505760512
1413393277555760384
1413393277605760512
1413393277655760384
1413393277705760512
1413393277755760384
1413393277805760512
1413393277855760384
1413393277905760512
1413393277955760384
1413393278005760512
1413393278055760384
1413393278105760512
1413393278155760384
1413393278205760512
1413393278255760384
1413393278305760512
1413393278355760384
1413393278405760512
1413393278455760384
1413393278505760512
1413393278555760384
1413393278605760512
1413393278655760384
1413393278705760512
1413393278755760384
1413393278805760512
1413393278855760384
1413393278905760512
1413393278955760384
1413393279005760512
1413393279055760384
1413393279105760512
1413393279155760384
1413393279205760512
1413393279255760384
1413393279305760512
1413393279355760384
1413393279405760512
1413393279455760384
1413393279505760512
1413393279555760384
1413393279605760512
1413393279655760384
1413393279705760512
1413393279755760384
1413393279805760512
1413393279855760384
1413393279905760512
1413393279955760384
1413393280005760512
1413393280055760384
1413393280105760512
1413393280155760384
1413393280205760512
1413393280255760384
1413393280305760512
1413393280355760384
1413393280405760512
1413393280455760384
1413393280505760512
1413393280555760384
1413393280605760512
1413393280655760384
1413393280705760512
1413393280755760384
1413393280805760512
1413393280855760384
1413393280905760512
1413393280955760384
1413393281005760512
1413393281055760384
1413393281105760512
1413393281155760384
1413393281205760512
1413393281255760384
1413393281305760512
1413393281355760384
1413393281405760512
1413393281455760384
1413393281505760512
1413393281555760384
1413393281605760512
1413393281655760384
1413393281705760512
1413393281755760384
1413393281805760512
1413393281855760384
1413393281905760512
1413393281955760384
1413393282005760512
1413393282055760384
1413393282105760512
1413393282155760384
1413393282205760512
1413393282255760384
1413393282305760512
1413393282355760384
1413393282405760512
1413393282455760384
1413393282505760512
1413393282555760384
1413393282605760512
1413393282655760384
1413393282705760512
1413393282755760384
1413393282805760512
1413393282855760384
1413393282905760512
1413393282955760384
1413393283005760512
1413393283055760384
1413393283105760512
1413393283155760384
1413393283205760512
1413393283255760384
1413393283305760512
1413393283355760384
1413393283405760512
1413393283455760384
1413393283505760512
1413393283555760384
1413393283605760512
1413393283655760384
1413393283705760512
1413393283755760384
1413393283805760512
1413393283855760384
1413393283905760512
1413393283955760384
1413393284005760512
1413393284055760384
1413393284105760512
1413393284155760384
1413393284205760512
1413393284255760384
1413393284305760512
1413393284355760384
1413393284405760512
1413393284455760384
1413393284505760512
1413393284555760384
1413393284605760512
1413393284655760384
1413393284705760512
1413393284755760384
1413393284805760512
1413393284855760384
1413393284905760512
1413393284955760384
1413393285005760512
1413393285055760384
1413393285105760512
1413393285155760384
1413393285205760512
1413393285255760384
1413393285305760512
1413393285355760384
1413393285405760512
1413393285455760384
1413393285505760512
1413393285555760384
1413393285605760512
1413393285655760384
1413393285705760512
1413393285755760384
1413393285805760512
1413393285855760384
1413393285905760512
1413393285955760384
1413393286005760512
1413393286055760384
1413393286105760512
1413393286155760384
1413393286205760512
1413393286255760384
1413393286305760512
1413393286355760384
1413393286405760512
1413393286455760384
1413393286505760512
1413393286555760384
1413393286605760512
1413393286655760384
1413393286705760512
1413393286755760384
1413393286805760512
1413393286855760384
1413393286905760512
1413393286955760384
1413393287005760512
1413393287055760384
1413393287105760512
1413393287155760384
1413393287205760512
1413393287255760384
1413393287305760512
1413393287355760384
1413393287405760512
1413393287455760384
1413393287505760512
1413393287555760384
1413393287605760512
1413393287655760384
1413393287705760512
1413393287755760384
1413393287805760512
1413393287855760384
1413393287905760512
1413393287955760384
1413393288005760512
1413393288055760384
1413393288105760512
1413393288155760384
1413393288205760512
1413393288255760384
1413393288305760512
1413393288355760384
1413393288405760512
1413393288455760384
1413393288505760512
1413393288555760384
1413393288605760512
1413393288655760384
1413393288705760512
1413393288755760384
1413393288805760512
1413393288855760384
1413393288905760512
1413393288955760384
1413393289005760512
1413393289055760384
1413393289105760512
1413393289155760384
1413393289205760512
1413393289255760384
1413393289305760512
1413393289355760384
1413393289405760512
1413393289455760384
1413393289505760512
1413393289555760384
1413393289605760512
1413393289655760384
1413393289705760512
1413393289755760384
1413393289805760512
1413393289855760384
1413393289905760512
1413393289955760384
1413393290005760512
1413393290055760384
1413393290105760512
1413393290155760384
1413393290205760512
1413393290255760384
1413393290305760512
1413393290355760384
1413393290405760512
1413393290455760384
1413393290505760512
1413393290555760384
1413393290605760512
1413393290655760384
1413393290705760512
1413393290755760384
1413393290805760512
1413393290855760384
1413393290905760512
1413393290955760384
1413393291005760512
1413393291055760384
1413393291105760512
1413393291155760384
1413393291205760512
1413393291255760384
1413393291305760512
1413393291355760384
1413393291405760512
1413393291455760384
1413393291505760512
1413393291555760384
1413393291605760512
1413393291655760384
1413393291705760512
1413393291755760384
1413393291805760512
1413393291855760384
1413393291905760512
1413393291955760384
1413393292005760512
1413393292055760384
1413393292105760512
1413393292155760384
1413393292205760512
1413393292255760384
1413393292305760512
1413393292355760384
1413393292405760512
1413393292455760384
1413393292505760512
1413393292555760384
1413393292605760512
1413393292655760384
1413393292705760512
1413393292755760384
1413393292805760512
1413393292855760384
1413393292905760512
1413393292955760384
1413393293005760512
1413393293055760384
1413393293105760512
1413393293155760384
1413393293205760512
1413393293255760384
1413393293305760512
1413393293355760384
1413393293405760512
1413393293455760384
1413393293505760512
1413393293555760384
1413393293605760512
1413393293655760384
1413393293705760512
1413393293755760384
1413393293805760512
1413393293855760384
1413393293905760512
1413393293955760384
1413393294005760512
1413393294055760384
1413393294105760512
1413393294155760384
1413393294205760512
1413393294255760384
1413393294305760512
1413393294355760384
1413393294405760512
1413393294455760384
1413393294505760512
1413393294555760384
1413393294605760512
1413393294655760384
1413393294705760512
1413393294755760384
1413393294805760512
1413393294855760384
1413393294905760512
1413393294955760384
1413393295005760512
1413393295055760384
1413393295105760512
1413393295155760384
1413393295205760512
1413393295255760384
1413393295305760512
1413393295355760384
1413393295405760512
1413393295455760384
1413393295505760512
1413393295555760384
1413393295605760512
1413393295655760384
1413393295705760512
1413393295755760384
1413393295805760512
1413393295855760384
1413393295905760512
1413393295955760384
1413393296005760512
1413393296055760384
1413393296105760512
1413393296155760384
1413393296205760512
1413393296255760384
1413393296305760512
1413393296355760384
1413393296405760512
1413393296455760384
1413393296505760512
1413393296555760384
1413393296605760512
1413393296655760384
1413393296705760512
1413393296755760384
1413393296805760512
1413393296855760384
1413393296905760512
1413393296955760384
1413393297005760512
1413393297055760384
1413393297105760512
1413393297155760384
1413393297205760512
1413393297255760384
1413393297305760512
1413393297355760384
1413393297405760512
1413393297455760384
1413393297505760512
1413393297555760384
1413393297605760512
1413393297655760384
1413393297705760512
1413393297755760384
1413393297805760512
1413393297855760384
1413393297905760512
1413393297955760384
1413393298005760512
1413393298055760384
1413393298105760512
1413393298155760384
1413393298205760512
1413393298255760384
1413393298305760512
1413393298355760384
1413393298405760512
1413393298455760384
1413393298505760512
1413393298555760384
1413393298605760512
1413393298655760384
1413393298705760512
1413393298755760384
1413393298805760512
1413393298855760384
1413393298905760512
1413393298955760384
1413393299005760512
1413393299055760384
1413393299105760512
1413393299155760384
1413393299205760512
1413393299255760384
1413393299305760512
1413393299355760384
1413393299405760512
1413393299455760384
1413393299505760512
1413393299555760384
1413393299605760512
1413393299655760384
1413393299705760512
1413393299755760384
1413393299805760512
1413393299855760384
1413393299905760512
1413393299955760384
1413393300005760512
1413393300055760384
1413393300105760512
1413393300155760384
1413393300205760512
1413393300255760384
1413393300305760512
1413393300355760384
1413393300405760512
1413393300455760384
1413393300505760512
1413393300555760384
1413393300605760512
1413393300655760384
1413393300705760512
1413393300755760384
1413393300805760512
1413393300855760384
1413393300905760512
1413393300955760384
1413393301005760512
1413393301055760384
1413393301105760512
1413393301155760384
1413393301205760512
1413393301255760384
1413393301305760512
1413393301355760384
1413393301405760512
1413393301455760384
1413393301505760512
1413393301555760384
1413393301605760512
1413393301655760384
1413393301705760512
1413393301755760384
1413393301805760512
1413393301855760384
1413393301905760512
1413393301955760384
1413393302005760512
1413393302055760384
1413393302105760512
1413393302155760384
1413393302205760512
1413393302255760384
1413393302305760512
1413393302355760384
1413393302405760512
1413393302455760384
1413393302505760512
1413393302555760384
1413393302605760512
1413393302655760384
1413393302705760512
1413393302755760384
1413393302805760512
1413393302855760384
1413393302905760512
1413393302955760384
1413393303005760512
1413393303055760384
1413393303105760512
1413393303155760384
1413393303205760512
1413393303255760384
1413393303305760512
1413393303355760384
1413393303405760512
1413393303455760384
1413393303505760512
1413393303555760384
1413393303605760512
1413393303655760384
1413393303705760512
1413393303755760384
1413393303805760512
1413393303855760384
1413393303905760512
1413393303955760384
1413393304005760512
1413393304055760384
1413393304105760512
1413393304155760384
1413393304205760512
1413393304255760384
1413393304305760512
1413393304355760384
1413393304405760512
1413393304455760384
1413393304505760512
1413393304555760384
1413393304605760512
1413393304655760384
1413393304705760512
1413393304755760384
1413393304805760512
1413393304855760384
1413393304905760512
1413393304955760384
1413393305005760512
1413393305055760384
1413393305105760512
1413393305155760384
1413393305205760512
1413393305255760384
1413393305305760512
1413393305355760384
1413393305405760512
1413393305455760384
1413393305505760512
1413393305555760384
1413393305605760512
1413393305655760384
1413393305705760512
1413393305755760384
1413393305805760512
1413393305855760384
1413393305905760512
1413393305955760384
1413393306005760512
1413393306055760384
1413393306105760512
1413393306155760384
1413393306205760512
1413393306255760384
1413393306305760512
1413393306355760384
1413393306405760512
1413393306455760384
1413393306505760512
1413393306555760384
1413393306605760512
1413393306655760384
1413393306705760512
1413393306755760384
1413393306805760512
1413393306855760384
1413393306905760512
1413393306955760384
1413393307005760512
1413393307055760384
1413393307105760512
1413393307155760384
1413393307205760512
1413393307255760384
1413393307305760512
1413393307355760384
1413393307405760512
1413393307455760384
1413393307505760512
1413393307555760384
1413393307605760512
1413393307655760384
1413393307705760512
1413393307755760384
1413393307805760512
1413393307855760384
1413393307905760512
1413393307955760384
1413393308005760512
1413393308055760384
1413393308105760512
1413393308155760384
1413393308205760512
1413393308255760384
1413393308305760512
1413393308355760384
1413393308405760512
1413393308455760384
1413393308505760512
1413393308555760384
1413393308605760512
1413393308655760384
1413393308705760512
1413393308755760384
1413393308805760512
1413393308855760384
1413393308905760512
1413393308955760384
1413393309005760512
1413393309055760384
1413393309105760512
1413393309155760384
1413393309205760512
1413393309255760384
1413393309305760512
1413393309355760384
1413393309405760512
1413393309455760384
1413393309505760512
1413393309555760384
1413393309605760512
1413393309655760384
1413393309705760512
1413393309755760384
1413393309805760512
1413393309855760384
1413393309905760512
1413393309955760384
1413393310005760512
1413393310055760384
1413393310105760512
1413393310155760384
1413393310205760512
1413393310255760384
1413393310305760512
1413393310355760384
1413393310405760512
1413393310455760384
1413393310505760512
1413393310555760384
1413393310605760512
1413393310655760384
1413393310705760512
1413393310755760384
1413393310805760512
1413393310855760384
1413393310905760512
1413393310955760384
1413393311005760512
1413393311055760384
1413393311105760512
1413393311155760384
1413393311205760512
1413393311255760384
1413393311305760512
1413393311355760384
1413393311405760512
1413393311455760384
1413393311505760512
1413393311555760384
1413393311605760512
1413393311655760384
1413393311705760512
1413393311755760384
1413393311805760512
1413393311855760384
1413393311905760512
1413393311955760384
1413393312005760512
1413393312055760384
1413393312105760512
1413393312155760384
1413393312205760512
1413393312255760384
1413393312305760512
1413393312355760384
1413393312405760512
1413393312455760384
1413393312505760512
1413393312555760384
1413393312605760512
1413393312655760384
1413393312705760512
1413393312755760384
1413393312805760512
1413393312855760384
1413393312905760512
1413393312955760384
1413393313005760512
1413393313055760384
1413393313105760512
1413393313155760384
1413393313205760512
1413393313255760384
1413393313305760512
1413393313355760384
1413393313405760512
1413393313455760384
1413393313505760512
1413393313555760384
1413393313605760512
1413393313655760384
1413393313705760512
1413393313755760384
1413393313805760512
1413393313855760384
1413393313905760512
1413393313955760384
1413393314005760512
1413393314055760384
1413393314105760512
1413393314155760384
1413393314205760512
1413393314255760384
1413393314305760512
1413393314355760384
1413393314405760512
1413393314455760384
1413393314505760512
1413393314555760384
1413393314605760512
1413393314655760384
1413393314705760512
1413393314755760384
1413393314805760512
1413393314855760384
1413393314905760512
1413393314955760384
1413393315005760512
1413393315055760384
1413393315105760512
1413393315155760384
1413393315205760512
1413393315255760384
1413393315305760512
1413393315355760384
1413393315405760512
1413393315455760384
1413393315505760512
1413393315555760384
1413393315605760512
1413393315655760384
1413393315705760512
1413393315755760384
1413393315805760512
1413393315855760384
1413393315905760512
1413393315955760384
1413393316005760512
1413393316055760384
1413393316105760512
1413393316155760384
1413393316205760512
1413393316255760384
1413393316305760512
1413393316355760384
1413393316405760512
1413393316455760384
1413393316505760512
1413393316555760384
1413393316605760512
1413393316655760384
1413393316705760512
1413393316755760384
1413393316805760512
1413393316855760384
1413393316905760512
1413393316955760384
1413393317005760512
1413393317055760384
1413393317105760512
1413393317155760384
1413393317205760512
1413393317255760384
1413393317305760512
1413393317355760384
1413393317405760512
1413393317455760384
1413393317505760512
1413393317555760384
1413393317605760512
1413393317655760384
1413393317705760512
1413393317755760384
1413393317805760512
1413393317855760384
1413393317905760512
1413393317955760384
1413393318005760512
1413393318055760384
1413393318105760512
1413393318155760384
1413393318205760512
1413393318255760384
1413393318305760512
1413393318355760384
1413393318405760512
1413393318455760384
1413393318505760512
1413393318555760384
1413393318605760512
1413393318655760384
1413393318705760512
1413393318755760384
1413393318805760512
1413393318855760384
1413393318905760512
1413393318955760384
1413393319005760512
1413393319055760384
1413393319105760512
1413393319155760384
1413393319205760512
1413393319255760384
1413393319305760512
1413393319355760384
1413393319405760512
1413393319455760384
1413393319505760512
1413393319555760384
1413393319605760512
1413393319655760384
1413393319705760512
1413393319755760384
1413393319805760512
1413393319855760384
1413393319905760512
1413393319955760384
1413393320005760512
1413393320055760384
1413393320105760512
1413393320155760384
1413393320205760512
1413393320255760384
1413393320305760512
1413393320355760384
1413393320405760512
1413393320455760384
1413393320505760512
1413393320555760384
1413393320605760512
1413393320655760384
1413393320705760512
1413393320755760384
1413393320805760512
1413393320855760384
1413393320905760512
1413393320955760384
1413393321005760512
1413393321055760384
1413393321105760512
1413393321155760384
1413393321205760512
1413393321255760384
1413393321305760512
1413393321355760384
1413393321405760512
1413393321455760384
1413393321505760512
1413393321555760384
1413393321605760512
1413393321655760384
1413393321705760512
1413393321755760384
1413393321805760512
1413393321855760384
1413393321905760512
1413393321955760384
1413393322005760512
1413393322055760384
1413393322105760512
1413393322155760384
1413393322205760512
1413393322255760384
1413393322305760512
1413393322355760384
1413393322405760512
1413393322455760384
1413393322505760512
1413393322555760384
1413393322605760512
1413393322655760384
1413393322705760512
1413393322755760384
1413393322805760512
1413393322855760384
1413393322905760512
1413393322955760384
1413393323005760512
1413393323055760384
1413393323105760512
1413393323155760384
1413393323205760512
1413393323255760384
1413393323305760512
1413393323355760384
1413393323405760512
1413393323455760384
1413393323505760512
1413393323555760384
1413393323605760512
1413393323655760384
1413393323705760512
1413393323755760384
1413393323805760512
1413393323855760384
1413393323905760512
1413393323955760384
1413393324005760512
1413393324055760384
1413393324105760512
1413393324155760384
1413393324205760512
1413393324255760384
1413393324305760512
1413393324355760384
1413393324405760512
1413393324455760384
1413393324505760512
1413393324555760384
1413393324605760512
1413393324655760384
1413393324705760512
1413393324755760384
1413393324805760512
1413393324855760384
1413393324905760512
1413393324955760384
1413393325005760512
1413393325055760384
1413393325105760512
1413393325155760384
1413393325205760512
1413393325255760384
1413393325305760512
1413393325355760384
1413393325405760512
1413393325455760384
1413393325505760512
1413393325555760384
1413393325605760512
1413393325655760384
1413393325705760512
1413393325755760384
1413393325805760512
1413393325855760384
1413393325905760512
1413393325955760384
1413393326005760512
1413393326055760384
1413393326105760512
1413393326155760384
1413393326205760512
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/V202.txt
================================================
1413393886005760512
1413393886055760384
1413393886105760512
1413393886155760384
1413393886205760512
1413393886255760384
1413393886305760512
1413393886355760384
1413393886405760512
1413393886455760384
1413393886505760512
1413393886555760384
1413393886605760512
1413393886655760384
1413393886705760512
1413393886755760384
1413393886805760512
1413393886855760384
1413393886905760512
1413393886955760384
1413393887005760512
1413393887055760384
1413393887105760512
1413393887155760384
1413393887205760512
1413393887255760384
1413393887305760512
1413393887355760384
1413393887405760512
1413393887455760384
1413393887505760512
1413393887555760384
1413393887605760512
1413393887655760384
1413393887705760512
1413393887755760384
1413393887805760512
1413393887855760384
1413393887905760512
1413393887955760384
1413393888005760512
1413393888055760384
1413393888105760512
1413393888155760384
1413393888205760512
1413393888255760384
1413393888305760512
1413393888355760384
1413393888405760512
1413393888455760384
1413393888505760512
1413393888555760384
1413393888605760512
1413393888655760384
1413393888705760512
1413393888755760384
1413393888805760512
1413393888855760384
1413393888905760512
1413393888955760384
1413393889005760512
1413393889055760384
1413393889105760512
1413393889155760384
1413393889205760512
1413393889255760384
1413393889305760512
1413393889355760384
1413393889405760512
1413393889455760384
1413393889505760512
1413393889555760384
1413393889605760512
1413393889655760384
1413393889705760512
1413393889755760384
1413393889805760512
1413393889855760384
1413393889905760512
1413393889955760384
1413393890005760512
1413393890055760384
1413393890105760512
1413393890155760384
1413393890205760512
1413393890255760384
1413393890305760512
1413393890355760384
1413393890405760512
1413393890455760384
1413393890505760512
1413393890555760384
1413393890605760512
1413393890655760384
1413393890705760512
1413393890755760384
1413393890805760512
1413393890855760384
1413393890905760512
1413393890955760384
1413393891005760512
1413393891055760384
1413393891105760512
1413393891155760384
1413393891205760512
1413393891255760384
1413393891305760512
1413393891355760384
1413393891405760512
1413393891455760384
1413393891505760512
1413393891555760384
1413393891605760512
1413393891655760384
1413393891705760512
1413393891755760384
1413393891805760512
1413393891855760384
1413393891905760512
1413393891955760384
1413393892005760512
1413393892055760384
1413393892105760512
1413393892155760384
1413393892205760512
1413393892255760384
1413393892305760512
1413393892355760384
1413393892405760512
1413393892455760384
1413393892505760512
1413393892555760384
1413393892605760512
1413393892655760384
1413393892705760512
1413393892755760384
1413393892805760512
1413393892855760384
1413393892905760512
1413393892955760384
1413393893005760512
1413393893055760384
1413393893105760512
1413393893155760384
1413393893205760512
1413393893255760384
1413393893305760512
1413393893355760384
1413393893405760512
1413393893455760384
1413393893505760512
1413393893555760384
1413393893605760512
1413393893655760384
1413393893705760512
1413393893755760384
1413393893805760512
1413393893855760384
1413393893905760512
1413393893955760384
1413393894005760512
1413393894055760384
1413393894105760512
1413393894155760384
1413393894205760512
1413393894255760384
1413393894305760512
1413393894355760384
1413393894405760512
1413393894455760384
1413393894505760512
1413393894555760384
1413393894605760512
1413393894655760384
1413393894705760512
1413393894755760384
1413393894805760512
1413393894855760384
1413393894905760512
1413393894955760384
1413393895005760512
1413393895055760384
1413393895105760512
1413393895155760384
1413393895205760512
1413393895255760384
1413393895305760512
1413393895355760384
1413393895405760512
1413393895455760384
1413393895505760512
1413393895555760384
1413393895605760512
1413393895655760384
1413393895705760512
1413393895755760384
1413393895805760512
1413393895855760384
1413393895905760512
1413393895955760384
1413393896005760512
1413393896055760384
1413393896105760512
1413393896155760384
1413393896205760512
1413393896255760384
1413393896305760512
1413393896355760384
1413393896405760512
1413393896455760384
1413393896505760512
1413393896555760384
1413393896605760512
1413393896655760384
1413393896705760512
1413393896755760384
1413393896805760512
1413393896855760384
1413393896905760512
1413393896955760384
1413393897005760512
1413393897055760384
1413393897105760512
1413393897155760384
1413393897205760512
1413393897255760384
1413393897305760512
1413393897355760384
1413393897405760512
1413393897455760384
1413393897505760512
1413393897555760384
1413393897605760512
1413393897655760384
1413393897705760512
1413393897755760384
1413393897805760512
1413393897855760384
1413393897905760512
1413393897955760384
1413393898005760512
1413393898055760384
1413393898105760512
1413393898155760384
1413393898205760512
1413393898255760384
1413393898305760512
1413393898355760384
1413393898405760512
1413393898455760384
1413393898505760512
1413393898555760384
1413393898605760512
1413393898655760384
1413393898705760512
1413393898755760384
1413393898805760512
1413393898855760384
1413393898905760512
1413393898955760384
1413393899005760512
1413393899055760384
1413393899105760512
1413393899155760384
1413393899205760512
1413393899255760384
1413393899305760512
1413393899355760384
1413393899405760512
1413393899455760384
1413393899505760512
1413393899555760384
1413393899605760512
1413393899655760384
1413393899705760512
1413393899755760384
1413393899805760512
1413393899855760384
1413393899905760512
1413393899955760384
1413393900005760512
1413393900055760384
1413393900105760512
1413393900155760384
1413393900205760512
1413393900255760384
1413393900305760512
1413393900355760384
1413393900405760512
1413393900455760384
1413393900505760512
1413393900555760384
1413393900605760512
1413393900655760384
1413393900705760512
1413393900755760384
1413393900805760512
1413393900855760384
1413393900905760512
1413393900955760384
1413393901005760512
1413393901055760384
1413393901105760512
1413393901155760384
1413393901205760512
1413393901255760384
1413393901305760512
1413393901355760384
1413393901405760512
1413393901455760384
1413393901505760512
1413393901555760384
1413393901605760512
1413393901655760384
1413393901705760512
1413393901755760384
1413393901805760512
1413393901855760384
1413393901905760512
1413393901955760384
1413393902005760512
1413393902055760384
1413393902105760512
1413393902155760384
1413393902205760512
1413393902255760384
1413393902305760512
1413393902355760384
1413393902405760512
1413393902455760384
1413393902505760512
1413393902555760384
1413393902605760512
1413393902655760384
1413393902705760512
1413393902755760384
1413393902805760512
1413393902855760384
1413393902905760512
1413393902955760384
1413393903005760512
1413393903055760384
1413393903105760512
1413393903155760384
1413393903205760512
1413393903255760384
1413393903305760512
1413393903355760384
1413393903405760512
1413393903455760384
1413393903505760512
1413393903555760384
1413393903605760512
1413393903655760384
1413393903705760512
1413393903755760384
1413393903805760512
1413393903855760384
1413393903905760512
1413393903955760384
1413393904005760512
1413393904055760384
1413393904105760512
1413393904155760384
1413393904205760512
1413393904255760384
1413393904305760512
1413393904355760384
1413393904405760512
1413393904455760384
1413393904505760512
1413393904555760384
1413393904605760512
1413393904655760384
1413393904705760512
1413393904755760384
1413393904805760512
1413393904855760384
1413393904905760512
1413393904955760384
1413393905005760512
1413393905055760384
1413393905105760512
1413393905155760384
1413393905205760512
1413393905255760384
1413393905305760512
1413393905355760384
1413393905405760512
1413393905455760384
1413393905505760512
1413393905555760384
1413393905605760512
1413393905655760384
1413393905705760512
1413393905755760384
1413393905805760512
1413393905855760384
1413393905905760512
1413393905955760384
1413393906005760512
1413393906055760384
1413393906105760512
1413393906155760384
1413393906205760512
1413393906255760384
1413393906305760512
1413393906355760384
1413393906405760512
1413393906455760384
1413393906505760512
1413393906555760384
1413393906605760512
1413393906655760384
1413393906705760512
1413393906755760384
1413393906805760512
1413393906855760384
1413393906905760512
1413393906955760384
1413393907005760512
1413393907055760384
1413393907105760512
1413393907155760384
1413393907205760512
1413393907255760384
1413393907305760512
1413393907355760384
1413393907405760512
1413393907455760384
1413393907505760512
1413393907555760384
1413393907605760512
1413393907655760384
1413393907705760512
1413393907755760384
1413393907805760512
1413393907855760384
1413393907905760512
1413393907955760384
1413393908005760512
1413393908055760384
1413393908105760512
1413393908155760384
1413393908205760512
1413393908255760384
1413393908305760512
1413393908355760384
1413393908405760512
1413393908455760384
1413393908505760512
1413393908555760384
1413393908605760512
1413393908655760384
1413393908705760512
1413393908755760384
1413393908805760512
1413393908855760384
1413393908905760512
1413393908955760384
1413393909005760512
1413393909055760384
1413393909105760512
1413393909155760384
1413393909205760512
1413393909255760384
1413393909305760512
1413393909355760384
1413393909405760512
1413393909455760384
1413393909505760512
1413393909555760384
1413393909605760512
1413393909655760384
1413393909705760512
1413393909755760384
1413393909805760512
1413393909855760384
1413393909905760512
1413393909955760384
1413393910005760512
1413393910055760384
1413393910105760512
1413393910155760384
1413393910205760512
1413393910255760384
1413393910305760512
1413393910355760384
1413393910405760512
1413393910455760384
1413393910505760512
1413393910555760384
1413393910605760512
1413393910655760384
1413393910705760512
1413393910755760384
1413393910805760512
1413393910855760384
1413393910905760512
1413393910955760384
1413393911005760512
1413393911055760384
1413393911105760512
1413393911155760384
1413393911205760512
1413393911255760384
1413393911305760512
1413393911355760384
1413393911405760512
1413393911455760384
1413393911505760512
1413393911555760384
1413393911605760512
1413393911655760384
1413393911705760512
1413393911755760384
1413393911805760512
1413393911855760384
1413393911905760512
1413393911955760384
1413393912005760512
1413393912055760384
1413393912105760512
1413393912155760384
1413393912205760512
1413393912255760384
1413393912305760512
1413393912355760384
1413393912405760512
1413393912455760384
1413393912505760512
1413393912555760384
1413393912605760512
1413393912655760384
1413393912705760512
1413393912755760384
1413393912805760512
1413393912855760384
1413393912905760512
1413393912955760384
1413393913005760512
1413393913055760384
1413393913105760512
1413393913155760384
1413393913205760512
1413393913255760384
1413393913305760512
1413393913355760384
1413393913405760512
1413393913455760384
1413393913505760512
1413393913555760384
1413393913605760512
1413393913655760384
1413393913705760512
1413393913755760384
1413393913805760512
1413393913855760384
1413393913905760512
1413393913955760384
1413393914005760512
1413393914055760384
1413393914105760512
1413393914155760384
1413393914205760512
1413393914255760384
1413393914305760512
1413393914355760384
1413393914405760512
1413393914455760384
1413393914505760512
1413393914555760384
1413393914605760512
1413393914655760384
1413393914705760512
1413393914755760384
1413393914805760512
1413393914855760384
1413393914905760512
1413393914955760384
1413393915005760512
1413393915055760384
1413393915105760512
1413393915155760384
1413393915205760512
1413393915255760384
1413393915305760512
1413393915355760384
1413393915405760512
1413393915455760384
1413393915505760512
1413393915555760384
1413393915605760512
1413393915655760384
1413393915705760512
1413393915755760384
1413393915805760512
1413393915855760384
1413393915905760512
1413393915955760384
1413393916005760512
1413393916055760384
1413393916105760512
1413393916155760384
1413393916205760512
1413393916255760384
1413393916305760512
1413393916355760384
1413393916405760512
1413393916455760384
1413393916505760512
1413393916555760384
1413393916605760512
1413393916655760384
1413393916705760512
1413393916755760384
1413393916805760512
1413393916855760384
1413393916905760512
1413393916955760384
1413393917005760512
1413393917055760384
1413393917105760512
1413393917155760384
1413393917205760512
1413393917255760384
1413393917305760512
1413393917355760384
1413393917405760512
1413393917455760384
1413393917505760512
1413393917555760384
1413393917605760512
1413393917655760384
1413393917705760512
1413393917755760384
1413393917805760512
1413393917855760384
1413393917905760512
1413393917955760384
1413393918005760512
1413393918055760384
1413393918105760512
1413393918155760384
1413393918205760512
1413393918255760384
1413393918305760512
1413393918355760384
1413393918405760512
1413393918455760384
1413393918505760512
1413393918555760384
1413393918605760512
1413393918655760384
1413393918705760512
1413393918755760384
1413393918805760512
1413393918855760384
1413393918905760512
1413393918955760384
1413393919005760512
1413393919055760384
1413393919105760512
1413393919155760384
1413393919205760512
1413393919255760384
1413393919305760512
1413393919355760384
1413393919405760512
1413393919455760384
1413393919505760512
1413393919555760384
1413393919605760512
1413393919655760384
1413393919705760512
1413393919755760384
1413393919805760512
1413393919855760384
1413393919905760512
1413393919955760384
1413393920005760512
1413393920055760384
1413393920105760512
1413393920155760384
1413393920205760512
1413393920255760384
1413393920305760512
1413393920355760384
1413393920405760512
1413393920455760384
1413393920505760512
1413393920555760384
1413393920605760512
1413393920655760384
1413393920705760512
1413393920755760384
1413393920805760512
1413393920855760384
1413393920905760512
1413393920955760384
1413393921005760512
1413393921055760384
1413393921105760512
1413393921155760384
1413393921205760512
1413393921255760384
1413393921305760512
1413393921355760384
1413393921405760512
1413393921455760384
1413393921505760512
1413393921555760384
1413393921605760512
1413393921655760384
1413393921705760512
1413393921755760384
1413393921805760512
1413393921855760384
1413393921905760512
1413393921955760384
1413393922005760512
1413393922055760384
1413393922105760512
1413393922155760384
1413393922205760512
1413393922255760384
1413393922305760512
1413393922355760384
1413393922405760512
1413393922455760384
1413393922505760512
1413393922555760384
1413393922605760512
1413393922655760384
1413393922705760512
1413393922755760384
1413393922805760512
1413393922855760384
1413393922905760512
1413393922955760384
1413393923005760512
1413393923055760384
1413393923105760512
1413393923155760384
1413393923205760512
1413393923255760384
1413393923305760512
1413393923355760384
1413393923405760512
1413393923455760384
1413393923505760512
1413393923555760384
1413393923605760512
1413393923655760384
1413393923705760512
1413393923755760384
1413393923805760512
1413393923855760384
1413393923905760512
1413393923955760384
1413393924005760512
1413393924055760384
1413393924105760512
1413393924155760384
1413393924205760512
1413393924255760384
1413393924305760512
1413393924355760384
1413393924405760512
1413393924455760384
1413393924505760512
1413393924555760384
1413393924605760512
1413393924655760384
1413393924705760512
1413393924755760384
1413393924805760512
1413393924855760384
1413393924905760512
1413393924955760384
1413393925005760512
1413393925055760384
1413393925105760512
1413393925155760384
1413393925205760512
1413393925255760384
1413393925305760512
1413393925355760384
1413393925405760512
1413393925455760384
1413393925505760512
1413393925555760384
1413393925605760512
1413393925655760384
1413393925705760512
1413393925755760384
1413393925805760512
1413393925855760384
1413393925905760512
1413393925955760384
1413393926005760512
1413393926055760384
1413393926105760512
1413393926155760384
1413393926205760512
1413393926255760384
1413393926305760512
1413393926355760384
1413393926405760512
1413393926455760384
1413393926505760512
1413393926555760384
1413393926605760512
1413393926655760384
1413393926705760512
1413393926755760384
1413393926805760512
1413393926855760384
1413393926905760512
1413393926955760384
1413393927005760512
1413393927055760384
1413393927105760512
1413393927155760384
1413393927205760512
1413393927255760384
1413393927305760512
1413393927355760384
1413393927405760512
1413393927455760384
1413393927505760512
1413393927555760384
1413393927605760512
1413393927655760384
1413393927705760512
1413393927755760384
1413393927805760512
1413393927855760384
1413393927905760512
1413393927955760384
1413393928005760512
1413393928055760384
1413393928105760512
1413393928155760384
1413393928205760512
1413393928255760384
1413393928305760512
1413393928355760384
1413393928405760512
1413393928455760384
1413393928505760512
1413393928555760384
1413393928605760512
1413393928655760384
1413393928705760512
1413393928755760384
1413393928805760512
1413393928855760384
1413393928905760512
1413393928955760384
1413393929005760512
1413393929055760384
1413393929105760512
1413393929155760384
1413393929205760512
1413393929255760384
1413393929305760512
1413393929355760384
1413393929405760512
1413393929455760384
1413393929505760512
1413393929555760384
1413393929605760512
1413393929655760384
1413393929705760512
1413393929755760384
1413393929805760512
1413393929855760384
1413393929905760512
1413393929955760384
1413393930005760512
1413393930055760384
1413393930105760512
1413393930155760384
1413393930205760512
1413393930255760384
1413393930305760512
1413393930355760384
1413393930405760512
1413393930455760384
1413393930505760512
1413393930555760384
1413393930605760512
1413393930655760384
1413393930705760512
1413393930755760384
1413393930805760512
1413393930855760384
1413393930905760512
1413393930955760384
1413393931005760512
1413393931055760384
1413393931105760512
1413393931155760384
1413393931205760512
1413393931255760384
1413393931305760512
1413393931355760384
1413393931405760512
1413393931455760384
1413393931505760512
1413393931555760384
1413393931605760512
1413393931655760384
1413393931705760512
1413393931755760384
1413393931805760512
1413393931855760384
1413393931905760512
1413393931955760384
1413393932005760512
1413393932055760384
1413393932105760512
1413393932155760384
1413393932205760512
1413393932255760384
1413393932305760512
1413393932355760384
1413393932405760512
1413393932455760384
1413393932505760512
1413393932555760384
1413393932605760512
1413393932655760384
1413393932705760512
1413393932755760384
1413393932805760512
1413393932855760384
1413393932905760512
1413393932955760384
1413393933005760512
1413393933055760384
1413393933105760512
1413393933155760384
1413393933205760512
1413393933255760384
1413393933305760512
1413393933355760384
1413393933405760512
1413393933455760384
1413393933505760512
1413393933555760384
1413393933605760512
1413393933655760384
1413393933705760512
1413393933755760384
1413393933805760512
1413393933855760384
1413393933905760512
1413393933955760384
1413393934005760512
1413393934055760384
1413393934105760512
1413393934155760384
1413393934205760512
1413393934255760384
1413393934305760512
1413393934355760384
1413393934405760512
1413393934455760384
1413393934505760512
1413393934555760384
1413393934605760512
1413393934655760384
1413393934705760512
1413393934755760384
1413393934805760512
1413393934855760384
1413393934905760512
1413393934955760384
1413393935005760512
1413393935055760384
1413393935105760512
1413393935155760384
1413393935205760512
1413393935255760384
1413393935305760512
1413393935355760384
1413393935405760512
1413393935455760384
1413393935505760512
1413393935555760384
1413393935605760512
1413393935655760384
1413393935705760512
1413393935755760384
1413393935805760512
1413393935855760384
1413393935905760512
1413393935955760384
1413393936005760512
1413393936055760384
1413393936105760512
1413393936155760384
1413393936205760512
1413393936255760384
1413393936305760512
1413393936355760384
1413393936405760512
1413393936455760384
1413393936505760512
1413393936555760384
1413393936605760512
1413393936655760384
1413393936705760512
1413393936755760384
1413393936805760512
1413393936855760384
1413393936905760512
1413393936955760384
1413393937005760512
1413393937055760384
1413393937105760512
1413393937155760384
1413393937205760512
1413393937255760384
1413393937305760512
1413393937355760384
1413393937405760512
1413393937455760384
1413393937505760512
1413393937555760384
1413393937605760512
1413393937655760384
1413393937705760512
1413393937755760384
1413393937805760512
1413393937855760384
1413393937905760512
1413393937955760384
1413393938005760512
1413393938055760384
1413393938105760512
1413393938155760384
1413393938205760512
1413393938255760384
1413393938305760512
1413393938355760384
1413393938405760512
1413393938455760384
1413393938505760512
1413393938555760384
1413393938605760512
1413393938655760384
1413393938705760512
1413393938755760384
1413393938805760512
1413393938855760384
1413393938905760512
1413393938955760384
1413393939005760512
1413393939055760384
1413393939105760512
1413393939155760384
1413393939205760512
1413393939255760384
1413393939305760512
1413393939355760384
1413393939405760512
1413393939455760384
1413393939505760512
1413393939555760384
1413393939605760512
1413393939655760384
1413393939705760512
1413393939755760384
1413393939805760512
1413393939855760384
1413393939905760512
1413393939955760384
1413393940005760512
1413393940055760384
1413393940105760512
1413393940155760384
1413393940205760512
1413393940255760384
1413393940305760512
1413393940355760384
1413393940405760512
1413393940455760384
1413393940505760512
1413393940555760384
1413393940605760512
1413393940655760384
1413393940705760512
1413393940755760384
1413393940805760512
1413393940855760384
1413393940905760512
1413393940955760384
1413393941005760512
1413393941055760384
1413393941105760512
1413393941155760384
1413393941205760512
1413393941255760384
1413393941305760512
1413393941355760384
1413393941405760512
1413393941455760384
1413393941505760512
1413393941555760384
1413393941605760512
1413393941655760384
1413393941705760512
1413393941755760384
1413393941805760512
1413393941855760384
1413393941905760512
1413393941955760384
1413393942005760512
1413393942055760384
1413393942105760512
1413393942155760384
1413393942205760512
1413393942255760384
1413393942305760512
1413393942355760384
1413393942405760512
1413393942455760384
1413393942505760512
1413393942555760384
1413393942605760512
1413393942655760384
1413393942705760512
1413393942755760384
1413393942805760512
1413393942855760384
1413393942905760512
1413393942955760384
1413393943005760512
1413393943055760384
1413393943105760512
1413393943155760384
1413393943205760512
1413393943255760384
1413393943305760512
1413393943355760384
1413393943405760512
1413393943455760384
1413393943505760512
1413393943555760384
1413393943605760512
1413393943655760384
1413393943705760512
1413393943755760384
1413393943805760512
1413393943855760384
1413393943905760512
1413393943955760384
1413393944005760512
1413393944055760384
1413393944105760512
1413393944155760384
1413393944205760512
1413393944255760384
1413393944305760512
1413393944355760384
1413393944405760512
1413393944455760384
1413393944505760512
1413393944555760384
1413393944605760512
1413393944655760384
1413393944705760512
1413393944755760384
1413393944805760512
1413393944855760384
1413393944905760512
1413393944955760384
1413393945005760512
1413393945055760384
1413393945105760512
1413393945155760384
1413393945205760512
1413393945255760384
1413393945305760512
1413393945355760384
1413393945405760512
1413393945455760384
1413393945505760512
1413393945555760384
1413393945605760512
1413393945655760384
1413393945705760512
1413393945755760384
1413393945805760512
1413393945855760384
1413393945905760512
1413393945955760384
1413393946005760512
1413393946055760384
1413393946105760512
1413393946155760384
1413393946205760512
1413393946255760384
1413393946305760512
1413393946355760384
1413393946405760512
1413393946455760384
1413393946505760512
1413393946555760384
1413393946605760512
1413393946655760384
1413393946705760512
1413393946755760384
1413393946805760512
1413393946855760384
1413393946905760512
1413393946955760384
1413393947005760512
1413393947055760384
1413393947105760512
1413393947155760384
1413393947205760512
1413393947255760384
1413393947305760512
1413393947355760384
1413393947405760512
1413393947455760384
1413393947505760512
1413393947555760384
1413393947605760512
1413393947655760384
1413393947705760512
1413393947755760384
1413393947805760512
1413393947855760384
1413393947905760512
1413393947955760384
1413393948005760512
1413393948055760384
1413393948105760512
1413393948155760384
1413393948205760512
1413393948255760384
1413393948305760512
1413393948355760384
1413393948405760512
1413393948455760384
1413393948505760512
1413393948555760384
1413393948605760512
1413393948655760384
1413393948705760512
1413393948755760384
1413393948805760512
1413393948855760384
1413393948905760512
1413393948955760384
1413393949005760512
1413393949055760384
1413393949105760512
1413393949155760384
1413393949205760512
1413393949255760384
1413393949305760512
1413393949355760384
1413393949405760512
1413393949455760384
1413393949505760512
1413393949555760384
1413393949605760512
1413393949655760384
1413393949705760512
1413393949755760384
1413393949805760512
1413393949855760384
1413393949905760512
1413393949955760384
1413393950005760512
1413393950055760384
1413393950105760512
1413393950155760384
1413393950205760512
1413393950255760384
1413393950305760512
1413393950355760384
1413393950405760512
1413393950455760384
1413393950505760512
1413393950555760384
1413393950605760512
1413393950655760384
1413393950705760512
1413393950755760384
1413393950805760512
1413393950855760384
1413393950905760512
1413393950955760384
1413393951005760512
1413393951055760384
1413393951105760512
1413393951155760384
1413393951205760512
1413393951255760384
1413393951305760512
1413393951355760384
1413393951405760512
1413393951455760384
1413393951505760512
1413393951555760384
1413393951605760512
1413393951655760384
1413393951705760512
1413393951755760384
1413393951805760512
1413393951855760384
1413393951905760512
1413393951955760384
1413393952005760512
1413393952055760384
1413393952105760512
1413393952155760384
1413393952205760512
1413393952255760384
1413393952305760512
1413393952355760384
1413393952405760512
1413393952455760384
1413393952505760512
1413393952555760384
1413393952605760512
1413393952655760384
1413393952705760512
1413393952755760384
1413393952805760512
1413393952855760384
1413393952905760512
1413393952955760384
1413393953005760512
1413393953055760384
1413393953105760512
1413393953155760384
1413393953205760512
1413393953255760384
1413393953305760512
1413393953355760384
1413393953405760512
1413393953455760384
1413393953505760512
1413393953555760384
1413393953605760512
1413393953655760384
1413393953705760512
1413393953755760384
1413393953805760512
1413393953855760384
1413393953905760512
1413393953955760384
1413393954005760512
1413393954055760384
1413393954105760512
1413393954155760384
1413393954205760512
1413393954255760384
1413393954305760512
1413393954355760384
1413393954405760512
1413393954455760384
1413393954505760512
1413393954555760384
1413393954605760512
1413393954655760384
1413393954705760512
1413393954755760384
1413393954805760512
1413393954855760384
1413393954905760512
1413393954955760384
1413393955005760512
1413393955055760384
1413393955105760512
1413393955155760384
1413393955205760512
1413393955255760384
1413393955305760512
1413393955355760384
1413393955405760512
1413393955455760384
1413393955505760512
1413393955555760384
1413393955605760512
1413393955655760384
1413393955705760512
1413393955755760384
1413393955805760512
1413393955855760384
1413393955905760512
1413393955955760384
1413393956005760512
1413393956055760384
1413393956105760512
1413393956155760384
1413393956205760512
1413393956255760384
1413393956305760512
1413393956355760384
1413393956405760512
1413393956455760384
1413393956505760512
1413393956555760384
1413393956605760512
1413393956655760384
1413393956705760512
1413393956755760384
1413393956805760512
1413393956855760384
1413393956905760512
1413393956955760384
1413393957005760512
1413393957055760384
1413393957105760512
1413393957155760384
1413393957205760512
1413393957255760384
1413393957305760512
1413393957355760384
1413393957405760512
1413393957455760384
1413393957505760512
1413393957555760384
1413393957605760512
1413393957655760384
1413393957705760512
1413393957755760384
1413393957805760512
1413393957855760384
1413393957905760512
1413393957955760384
1413393958005760512
1413393958055760384
1413393958105760512
1413393958155760384
1413393958205760512
1413393958255760384
1413393958305760512
1413393958355760384
1413393958405760512
1413393958455760384
1413393958505760512
1413393958555760384
1413393958605760512
1413393958655760384
1413393958705760512
1413393958755760384
1413393958805760512
1413393958855760384
1413393958905760512
1413393958955760384
1413393959005760512
1413393959055760384
1413393959105760512
1413393959155760384
1413393959205760512
1413393959255760384
1413393959305760512
1413393959355760384
1413393959405760512
1413393959455760384
1413393959505760512
1413393959555760384
1413393959605760512
1413393959655760384
1413393959705760512
1413393959755760384
1413393959805760512
1413393959855760384
1413393959905760512
1413393959955760384
1413393960005760512
1413393960055760384
1413393960105760512
1413393960155760384
1413393960205760512
1413393960255760384
1413393960305760512
1413393960355760384
1413393960405760512
1413393960455760384
1413393960505760512
1413393960555760384
1413393960605760512
1413393960655760384
1413393960705760512
1413393960755760384
1413393960805760512
1413393960855760384
1413393960905760512
1413393960955760384
1413393961005760512
1413393961055760384
1413393961105760512
1413393961155760384
1413393961205760512
1413393961255760384
1413393961305760512
1413393961355760384
1413393961405760512
1413393961455760384
1413393961505760512
1413393961555760384
1413393961605760512
1413393961655760384
1413393961705760512
1413393961755760384
1413393961805760512
1413393961855760384
1413393961905760512
1413393961955760384
1413393962005760512
1413393962055760384
1413393962105760512
1413393962155760384
1413393962205760512
1413393962255760384
1413393962305760512
1413393962355760384
1413393962405760512
1413393962455760384
1413393962505760512
1413393962555760384
1413393962605760512
1413393962655760384
1413393962705760512
1413393962755760384
1413393962805760512
1413393962855760384
1413393962905760512
1413393962955760384
1413393963005760512
1413393963055760384
1413393963105760512
1413393963155760384
1413393963205760512
1413393963255760384
1413393963305760512
1413393963355760384
1413393963405760512
1413393963455760384
1413393963505760512
1413393963555760384
1413393963605760512
1413393963655760384
1413393963705760512
1413393963755760384
1413393963805760512
1413393963855760384
1413393963905760512
1413393963955760384
1413393964005760512
1413393964055760384
1413393964105760512
1413393964155760384
1413393964205760512
1413393964255760384
1413393964305760512
1413393964355760384
1413393964405760512
1413393964455760384
1413393964505760512
1413393964555760384
1413393964605760512
1413393964655760384
1413393964705760512
1413393964755760384
1413393964805760512
1413393964855760384
1413393964905760512
1413393964955760384
1413393965005760512
1413393965055760384
1413393965105760512
1413393965155760384
1413393965205760512
1413393965255760384
1413393965305760512
1413393965355760384
1413393965405760512
1413393965455760384
1413393965505760512
1413393965555760384
1413393965605760512
1413393965655760384
1413393965705760512
1413393965755760384
1413393965805760512
1413393965855760384
1413393965905760512
1413393965955760384
1413393966005760512
1413393966055760384
1413393966105760512
1413393966155760384
1413393966205760512
1413393966255760384
1413393966305760512
1413393966355760384
1413393966405760512
1413393966455760384
1413393966505760512
1413393966555760384
1413393966605760512
1413393966655760384
1413393966705760512
1413393966755760384
1413393966805760512
1413393966855760384
1413393966905760512
1413393966955760384
1413393967005760512
1413393967055760384
1413393967105760512
1413393967155760384
1413393967205760512
1413393967255760384
1413393967305760512
1413393967355760384
1413393967405760512
1413393967455760384
1413393967505760512
1413393967555760384
1413393967605760512
1413393967655760384
1413393967705760512
1413393967755760384
1413393967805760512
1413393967855760384
1413393967905760512
1413393967955760384
1413393968005760512
1413393968055760384
1413393968105760512
1413393968155760384
1413393968205760512
1413393968255760384
1413393968305760512
1413393968355760384
1413393968405760512
1413393968455760384
1413393968505760512
1413393968555760384
1413393968605760512
1413393968655760384
1413393968705760512
1413393968755760384
1413393968805760512
1413393968855760384
1413393968905760512
1413393968955760384
1413393969005760512
1413393969055760384
1413393969105760512
1413393969155760384
1413393969205760512
1413393969255760384
1413393969305760512
1413393969355760384
1413393969405760512
1413393969455760384
1413393969505760512
1413393969555760384
1413393969605760512
1413393969655760384
1413393969705760512
1413393969755760384
1413393969805760512
1413393969855760384
1413393969905760512
1413393969955760384
1413393970005760512
1413393970055760384
1413393970105760512
1413393970155760384
1413393970205760512
1413393970255760384
1413393970305760512
1413393970355760384
1413393970405760512
1413393970455760384
1413393970505760512
1413393970555760384
1413393970605760512
1413393970655760384
1413393970705760512
1413393970755760384
1413393970805760512
1413393970855760384
1413393970905760512
1413393970955760384
1413393971005760512
1413393971055760384
1413393971105760512
1413393971155760384
1413393971205760512
1413393971255760384
1413393971305760512
1413393971355760384
1413393971405760512
1413393971455760384
1413393971505760512
1413393971555760384
1413393971605760512
1413393971655760384
1413393971705760512
1413393971755760384
1413393971805760512
1413393971855760384
1413393971905760512
1413393971955760384
1413393972005760512
1413393972055760384
1413393972105760512
1413393972155760384
1413393972205760512
1413393972255760384
1413393972305760512
1413393972355760384
1413393972405760512
1413393972455760384
1413393972505760512
1413393972555760384
1413393972605760512
1413393972655760384
1413393972705760512
1413393972755760384
1413393972805760512
1413393972855760384
1413393972905760512
1413393972955760384
1413393973005760512
1413393973055760384
1413393973105760512
1413393973155760384
1413393973205760512
1413393973255760384
1413393973305760512
1413393973355760384
1413393973405760512
1413393973455760384
1413393973505760512
1413393973555760384
1413393973605760512
1413393973655760384
1413393973705760512
1413393973755760384
1413393973805760512
1413393973855760384
1413393973905760512
1413393973955760384
1413393974005760512
1413393974055760384
1413393974105760512
1413393974155760384
1413393974205760512
1413393974255760384
1413393974305760512
1413393974355760384
1413393974405760512
1413393974455760384
1413393974505760512
1413393974555760384
1413393974605760512
1413393974655760384
1413393974705760512
1413393974755760384
1413393974805760512
1413393974855760384
1413393974905760512
1413393974955760384
1413393975005760512
1413393975055760384
1413393975105760512
1413393975155760384
1413393975205760512
1413393975255760384
1413393975305760512
1413393975355760384
1413393975405760512
1413393975455760384
1413393975505760512
1413393975555760384
1413393975605760512
1413393975655760384
1413393975705760512
1413393975755760384
1413393975805760512
1413393975855760384
1413393975905760512
1413393975955760384
1413393976005760512
1413393976055760384
1413393976105760512
1413393976155760384
1413393976205760512
1413393976255760384
1413393976305760512
1413393976355760384
1413393976405760512
1413393976455760384
1413393976505760512
1413393976555760384
1413393976605760512
1413393976655760384
1413393976705760512
1413393976755760384
1413393976805760512
1413393976855760384
1413393976905760512
1413393976955760384
1413393977005760512
1413393977055760384
1413393977105760512
1413393977155760384
1413393977205760512
1413393977255760384
1413393977305760512
1413393977355760384
1413393977405760512
1413393977455760384
1413393977505760512
1413393977555760384
1413393977605760512
1413393977655760384
1413393977705760512
1413393977755760384
1413393977805760512
1413393977855760384
1413393977905760512
1413393977955760384
1413393978005760512
1413393978055760384
1413393978105760512
1413393978155760384
1413393978205760512
1413393978255760384
1413393978305760512
1413393978355760384
1413393978405760512
1413393978455760384
1413393978505760512
1413393978555760384
1413393978605760512
1413393978655760384
1413393978705760512
1413393978755760384
1413393978805760512
1413393978855760384
1413393978905760512
1413393978955760384
1413393979005760512
1413393979055760384
1413393979105760512
1413393979155760384
1413393979205760512
1413393979255760384
1413393979305760512
1413393979355760384
1413393979405760512
1413393979455760384
1413393979505760512
1413393979555760384
1413393979605760512
1413393979655760384
1413393979705760512
1413393979755760384
1413393979805760512
1413393979855760384
1413393979905760512
1413393979955760384
1413393980005760512
1413393980055760384
1413393980105760512
1413393980155760384
1413393980205760512
1413393980255760384
1413393980305760512
1413393980355760384
1413393980405760512
1413393980455760384
1413393980505760512
1413393980555760384
1413393980605760512
1413393980655760384
1413393980705760512
1413393980755760384
1413393980805760512
1413393980855760384
1413393980905760512
1413393980955760384
1413393981005760512
1413393981055760384
1413393981105760512
1413393981155760384
1413393981205760512
1413393981255760384
1413393981305760512
1413393981355760384
1413393981405760512
1413393981455760384
1413393981505760512
1413393981555760384
1413393981605760512
1413393981655760384
1413393981705760512
1413393981755760384
1413393981805760512
1413393981855760384
1413393981905760512
1413393981955760384
1413393982005760512
1413393982055760384
1413393982105760512
1413393982155760384
1413393982205760512
1413393982255760384
1413393982305760512
1413393982355760384
1413393982405760512
1413393982455760384
1413393982505760512
1413393982555760384
1413393982605760512
1413393982655760384
1413393982705760512
1413393982755760384
1413393982805760512
1413393982855760384
1413393982905760512
1413393982955760384
1413393983005760512
1413393983055760384
1413393983105760512
1413393983155760384
1413393983205760512
1413393983255760384
1413393983305760512
1413393983355760384
1413393983405760512
1413393983455760384
1413393983505760512
1413393983555760384
1413393983605760512
1413393983655760384
1413393983705760512
1413393983755760384
1413393983805760512
1413393983855760384
1413393983905760512
1413393983955760384
1413393984005760512
1413393984055760384
1413393984105760512
1413393984155760384
1413393984205760512
1413393984255760384
1413393984305760512
1413393984355760384
1413393984405760512
1413393984455760384
1413393984505760512
1413393984555760384
1413393984605760512
1413393984655760384
1413393984705760512
1413393984755760384
1413393984805760512
1413393984855760384
1413393984905760512
1413393984955760384
1413393985005760512
1413393985055760384
1413393985105760512
1413393985155760384
1413393985205760512
1413393985255760384
1413393985305760512
1413393985355760384
1413393985405760512
1413393985455760384
1413393985505760512
1413393985555760384
1413393985605760512
1413393985655760384
1413393985705760512
1413393985755760384
1413393985805760512
1413393985855760384
1413393985905760512
1413393985955760384
1413393986005760512
1413393986055760384
1413393986105760512
1413393986155760384
1413393986205760512
1413393986255760384
1413393986305760512
1413393986355760384
1413393986405760512
1413393986455760384
1413393986505760512
1413393986555760384
1413393986605760512
1413393986655760384
1413393986705760512
1413393986755760384
1413393986805760512
1413393986855760384
1413393986905760512
1413393986955760384
1413393987005760512
1413393987055760384
1413393987105760512
1413393987155760384
1413393987205760512
1413393987255760384
1413393987305760512
1413393987355760384
1413393987405760512
1413393987455760384
1413393987505760512
1413393987555760384
1413393987605760512
1413393987655760384
1413393987705760512
1413393987755760384
1413393987805760512
1413393987855760384
1413393987905760512
1413393987955760384
1413393988005760512
1413393988055760384
1413393988105760512
1413393988155760384
1413393988205760512
1413393988255760384
1413393988305760512
1413393988355760384
1413393988405760512
1413393988455760384
1413393988505760512
1413393988555760384
1413393988605760512
1413393988655760384
1413393988705760512
1413393988755760384
1413393988805760512
1413393988855760384
1413393988905760512
1413393988955760384
1413393989005760512
1413393989055760384
1413393989105760512
1413393989155760384
1413393989205760512
1413393989255760384
1413393989305760512
1413393989355760384
1413393989405760512
1413393989455760384
1413393989505760512
1413393989555760384
1413393989605760512
1413393989655760384
1413393989705760512
1413393989755760384
1413393989805760512
1413393989855760384
1413393989905760512
1413393989955760384
1413393990005760512
1413393990055760384
1413393990105760512
1413393990155760384
1413393990205760512
1413393990255760384
1413393990305760512
1413393990355760384
1413393990405760512
1413393990455760384
1413393990505760512
1413393990555760384
1413393990605760512
1413393990655760384
1413393990705760512
1413393990755760384
1413393990805760512
1413393990855760384
1413393990905760512
1413393990955760384
1413393991005760512
1413393991055760384
1413393991105760512
1413393991155760384
1413393991205760512
1413393991255760384
1413393991305760512
1413393991355760384
1413393991405760512
1413393991455760384
1413393991505760512
1413393991555760384
1413393991605760512
1413393991655760384
1413393991705760512
1413393991755760384
1413393991805760512
1413393991855760384
1413393991905760512
1413393991955760384
1413393992005760512
1413393992055760384
1413393992105760512
1413393992155760384
1413393992205760512
1413393992255760384
1413393992305760512
1413393992355760384
1413393992405760512
1413393992455760384
1413393992505760512
1413393992555760384
1413393992605760512
1413393992655760384
1413393992705760512
1413393992755760384
1413393992805760512
1413393992855760384
1413393992905760512
1413393992955760384
1413393993005760512
1413393993055760384
1413393993105760512
1413393993155760384
1413393993205760512
1413393993255760384
1413393993305760512
1413393993355760384
1413393993405760512
1413393993455760384
1413393993505760512
1413393993555760384
1413393993605760512
1413393993655760384
1413393993705760512
1413393993755760384
1413393993805760512
1413393993855760384
1413393993905760512
1413393993955760384
1413393994005760512
1413393994055760384
1413393994105760512
1413393994155760384
1413393994205760512
1413393994255760384
1413393994305760512
1413393994355760384
1413393994405760512
1413393994455760384
1413393994505760512
1413393994555760384
1413393994605760512
1413393994655760384
1413393994705760512
1413393994755760384
1413393994805760512
1413393994855760384
1413393994905760512
1413393994955760384
1413393995005760512
1413393995055760384
1413393995105760512
1413393995155760384
1413393995205760512
1413393995255760384
1413393995305760512
1413393995355760384
1413393995405760512
1413393995455760384
1413393995505760512
1413393995555760384
1413393995605760512
1413393995655760384
1413393995705760512
1413393995755760384
1413393995805760512
1413393995855760384
1413393995905760512
1413393995955760384
1413393996005760512
1413393996055760384
1413393996105760512
1413393996155760384
1413393996205760512
1413393996255760384
1413393996305760512
1413393996355760384
1413393996405760512
1413393996455760384
1413393996505760512
1413393996555760384
1413393996605760512
1413393996655760384
1413393996705760512
1413393996755760384
1413393996805760512
1413393996855760384
1413393996905760512
1413393996955760384
1413393997005760512
1413393997055760384
1413393997105760512
1413393997155760384
1413393997205760512
1413393997255760384
1413393997305760512
1413393997355760384
1413393997405760512
1413393997455760384
1413393997505760512
1413393997555760384
1413393997605760512
1413393997655760384
1413393997705760512
1413393997755760384
1413393997805760512
1413393997855760384
1413393997905760512
1413393997955760384
1413393998005760512
1413393998055760384
1413393998105760512
1413393998155760384
1413393998205760512
1413393998255760384
1413393998305760512
1413393998355760384
1413393998405760512
1413393998455760384
1413393998505760512
1413393998555760384
1413393998605760512
1413393998655760384
1413393998705760512
1413393998755760384
1413393998805760512
1413393998855760384
1413393998905760512
1413393998955760384
1413393999005760512
1413393999055760384
1413393999105760512
1413393999155760384
1413393999205760512
1413393999255760384
1413393999305760512
1413393999355760384
1413393999405760512
1413393999455760384
1413393999505760512
1413393999555760384
1413393999605760512
1413393999655760384
1413393999705760512
1413393999755760384
1413393999805760512
1413393999855760384
1413393999905760512
1413393999955760384
1413394000005760512
1413394000055760384
1413394000105760512
1413394000155760384
1413394000205760512
1413394000255760384
1413394000305760512
1413394000355760384
1413394000405760512
1413394000455760384
1413394000505760512
1413394000555760384
1413394000605760512
1413394000655760384
1413394000705760512
1413394000755760384
1413394000805760512
1413394000855760384
1413394000905760512
1413394000955760384
1413394001005760512
1413394001055760384
1413394001105760512
1413394001155760384
1413394001205760512
1413394001255760384
1413394001305760512
1413394001355760384
1413394001405760512
1413394001455760384
1413394001505760512
1413394001555760384
1413394001605760512
1413394001655760384
1413394001705760512
1413394001755760384
1413394001805760512
1413394001855760384
1413394001905760512
1413394001955760384
1413394002005760512
1413394002055760384
1413394002105760512
1413394002155760384
1413394002205760512
1413394002255760384
1413394002305760512
1413394002355760384
1413394002405760512
1413394002455760384
1413394002505760512
1413394002555760384
1413394002605760512
1413394002655760384
1413394002705760512
1413394002755760384
1413394002805760512
1413394002855760384
1413394002905760512
1413394002955760384
1413394003005760512
1413394003055760384
1413394003105760512
1413394003155760384
1413394003205760512
1413394003255760384
1413394003305760512
1413394003355760384
================================================
FILE: Examples/Stereo/EuRoC_TimeStamps/V203.txt
================================================
1413394881605760512
1413394881655760384
1413394881705760512
1413394881755760384
1413394881805760512
1413394881855760384
1413394881905760512
1413394881955760384
1413394882005760512
1413394882055760384
1413394882105760512
1413394882155760384
1413394882205760512
1413394882255760384
1413394882305760512
1413394882355760384
1413394882405760512
1413394882455760384
1413394882505760512
1413394882555760384
1413394882605760512
1413394882655760384
1413394882705760512
1413394882755760384
1413394882805760512
1413394882855760384
1413394882905760512
1413394882955760384
1413394883005760512
1413394883055760384
1413394883105760512
1413394883155760384
1413394883205760512
1413394883255760384
1413394883305760512
1413394883355760384
1413394883405760512
1413394883455760384
1413394883505760512
1413394883555760384
1413394883605760512
1413394883655760384
1413394883705760512
1413394883755760384
1413394883805760512
1413394883855760384
1413394883905760512
1413394883955760384
1413394884005760512
1413394884055760384
1413394884105760512
1413394884155760384
1413394884205760512
1413394884255760384
1413394884305760512
1413394884355760384
1413394884405760512
1413394884455760384
1413394884505760512
1413394884555760384
1413394884605760512
1413394884655760384
1413394884705760512
1413394884755760384
1413394884805760512
1413394884855760384
1413394884905760512
1413394884955760384
1413394885005760512
1413394885055760384
1413394885105760512
1413394885155760384
1413394885205760512
1413394885255760384
1413394885305760512
1413394885355760384
1413394885405760512
1413394885455760384
1413394885505760512
1413394885555760384
1413394885605760512
1413394885655760384
1413394885705760512
1413394885755760384
1413394885805760512
1413394885855760384
1413394885905760512
1413394885955760384
1413394886005760512
1413394886055760384
1413394886105760512
1413394886155760384
1413394886205760512
1413394886255760384
1413394886305760512
1413394886355760384
1413394886405760512
1413394886455760384
1413394886505760512
1413394886555760384
1413394886605760512
1413394886655760384
1413394886705760512
1413394886755760384
1413394886805760512
1413394886855760384
1413394886905760512
1413394886955760384
1413394887005760512
1413394887055760384
1413394887105760512
1413394887155760384
1413394887205760512
1413394887255760384
1413394887305760512
1413394887355760384
1413394887405760512
1413394887455760384
1413394887505760512
1413394887555760384
1413394887605760512
1413394887655760384
1413394887705760512
1413394887755760384
1413394887805760512
1413394887855760384
1413394887905760512
1413394887955760384
1413394888005760512
1413394888055760384
1413394888105760512
1413394888155760384
1413394888205760512
1413394888255760384
1413394888305760512
1413394888355760384
1413394888405760512
1413394888455760384
1413394888505760512
1413394888555760384
1413394888605760512
1413394888655760384
1413394888705760512
1413394888755760384
1413394888805760512
1413394888855760384
1413394888905760512
1413394888955760384
1413394889005760512
1413394889055760384
1413394889105760512
1413394889155760384
1413394889205760512
1413394889255760384
1413394889305760512
1413394889355760384
1413394889405760512
1413394889455760384
1413394889505760512
1413394889555760384
1413394889605760512
1413394889655760384
1413394889705760512
1413394889755760384
1413394889805760512
1413394889855760384
1413394889905760512
1413394889955760384
1413394890005760512
1413394890055760384
1413394890105760512
1413394890155760384
1413394890205760512
1413394890255760384
1413394890305760512
1413394890355760384
1413394890405760512
1413394890455760384
1413394890505760512
1413394890555760384
1413394890605760512
1413394890655760384
1413394890705760512
1413394890755760384
1413394890805760512
1413394890855760384
1413394890905760512
1413394890955760384
1413394891005760512
1413394891055760384
1413394891105760512
1413394891155760384
1413394891205760512
1413394891255760384
1413394891305760512
1413394891355760384
1413394891405760512
1413394891455760384
1413394891505760512
1413394891555760384
1413394891605760512
1413394891655760384
1413394891705760512
1413394891755760384
1413394891805760512
1413394891855760384
1413394891905760512
1413394891955760384
1413394892005760512
1413394892055760384
1413394892105760512
1413394892155760384
1413394892205760512
1413394892255760384
1413394892305760512
1413394892355760384
1413394892405760512
1413394892455760384
1413394892505760512
1413394892555760384
1413394892605760512
1413394892655760384
1413394892705760512
1413394892755760384
1413394892805760512
1413394892855760384
1413394892905760512
1413394892955760384
1413394893005760512
1413394893055760384
1413394893105760512
1413394893155760384
1413394893205760512
1413394893255760384
1413394893305760512
1413394893355760384
1413394893405760512
1413394893455760384
1413394893505760512
1413394893555760384
1413394893605760512
1413394893655760384
1413394893705760512
1413394893755760384
1413394893805760512
1413394893855760384
1413394893905760512
1413394893955760384
1413394894005760512
1413394894055760384
1413394894105760512
1413394894155760384
1413394894205760512
1413394894255760384
1413394894305760512
1413394894355760384
1413394894405760512
1413394894455760384
1413394894505760512
1413394894555760384
1413394894605760512
1413394894655760384
1413394894705760512
1413394894755760384
1413394894805760512
1413394894855760384
1413394894905760512
1413394894955760384
1413394895005760512
1413394895055760384
1413394895105760512
1413394895155760384
1413394895205760512
1413394895255760384
1413394895305760512
1413394895355760384
1413394895405760512
1413394895455760384
1413394895505760512
1413394895555760384
1413394895605760512
1413394895655760384
1413394895705760512
1413394895755760384
1413394895805760512
1413394895855760384
1413394895905760512
1413394895955760384
1413394896005760512
1413394896055760384
1413394896105760512
1413394896155760384
1413394896205760512
1413394896255760384
1413394896305760512
1413394896355760384
1413394896405760512
1413394896455760384
1413394896505760512
1413394896555760384
1413394896605760512
1413394896655760384
1413394896705760512
1413394896755760384
1413394896805760512
1413394896855760384
1413394896905760512
1413394896955760384
1413394897005760512
1413394897055760384
1413394897105760512
1413394897155760384
1413394897205760512
1413394897255760384
1413394897305760512
1413394897355760384
1413394897405760512
1413394897455760384
1413394897505760512
1413394897555760384
1413394897605760512
1413394897655760384
1413394897705760512
1413394897755760384
1413394897805760512
1413394897855760384
1413394897905760512
1413394897955760384
1413394898005760512
1413394898055760384
1413394898105760512
1413394898155760384
1413394898205760512
1413394898255760384
1413394898305760512
1413394898355760384
1413394898405760512
1413394898455760384
1413394898505760512
1413394898555760384
1413394898605760512
1413394898655760384
1413394898705760512
1413394898755760384
1413394898805760512
1413394898855760384
1413394898905760512
1413394898955760384
1413394899005760512
1413394899055760384
1413394899105760512
1413394899155760384
1413394899205760512
1413394899255760384
1413394899305760512
1413394899355760384
1413394899405760512
1413394899455760384
1413394899505760512
1413394899555760384
1413394899605760512
1413394899655760384
1413394899705760512
1413394899755760384
1413394899805760512
1413394899855760384
1413394899905760512
1413394899955760384
1413394900005760512
1413394900055760384
1413394900105760512
1413394900155760384
1413394900205760512
1413394900255760384
1413394900305760512
1413394900355760384
1413394900405760512
1413394900455760384
1413394900505760512
1413394900555760384
1413394900605760512
1413394900655760384
1413394900705760512
1413394900755760384
1413394900805760512
1413394900855760384
1413394900905760512
1413394900955760384
1413394901005760512
1413394901055760384
1413394901105760512
1413394901155760384
1413394901205760512
1413394901255760384
1413394901305760512
1413394901355760384
1413394901405760512
1413394901455760384
1413394901505760512
1413394901555760384
1413394901605760512
1413394901655760384
1413394901705760512
1413394901755760384
1413394901805760512
1413394901855760384
1413394901905760512
1413394901955760384
1413394902005760512
1413394902055760384
1413394902105760512
1413394902155760384
1413394902205760512
1413394902255760384
1413394902305760512
1413394902355760384
1413394902405760512
1413394902455760384
1413394902505760512
1413394902555760384
1413394902605760512
1413394902655760384
1413394902705760512
1413394902755760384
1413394902805760512
1413394902855760384
1413394902905760512
1413394902955760384
1413394903055760384
1413394903155760384
1413394903255760384
1413394903355760384
1413394903455760384
1413394903555760384
1413394903605760512
1413394903655760384
1413394903705760512
1413394903755760384
1413394903805760512
1413394903855760384
1413394903905760512
1413394903955760384
1413394904005760512
1413394904055760384
1413394904105760512
1413394904155760384
1413394904205760512
1413394904255760384
1413394904305760512
1413394904355760384
1413394904405760512
1413394904455760384
1413394904505760512
1413394904555760384
1413394904605760512
1413394904655760384
1413394904705760512
1413394904755760384
1413394904805760512
1413394904855760384
1413394904905760512
1413394904955760384
1413394905005760512
1413394905055760384
1413394905105760512
1413394905155760384
1413394905205760512
1413394905255760384
1413394905305760512
1413394905355760384
1413394905405760512
1413394905455760384
1413394905505760512
1413394905555760384
1413394905605760512
1413394905655760384
1413394905705760512
1413394905755760384
1413394905805760512
1413394905855760384
1413394905905760512
1413394905955760384
1413394906005760512
1413394906055760384
1413394906105760512
1413394906155760384
1413394906205760512
1413394906255760384
1413394906305760512
1413394906355760384
1413394906405760512
1413394906455760384
1413394906505760512
1413394906555760384
1413394906605760512
1413394906655760384
1413394906705760512
1413394906755760384
1413394906805760512
1413394906855760384
1413394906905760512
1413394906955760384
1413394907005760512
1413394907055760384
1413394907105760512
1413394907155760384
1413394907205760512
1413394907255760384
1413394907305760512
1413394907355760384
1413394907405760512
1413394907455760384
1413394907505760512
1413394907555760384
1413394907605760512
1413394907655760384
1413394907705760512
1413394907755760384
1413394907805760512
1413394907855760384
1413394907905760512
1413394907955760384
1413394908005760512
1413394908055760384
1413394908105760512
1413394908155760384
1413394908205760512
1413394908255760384
1413394908305760512
1413394908355760384
1413394908405760512
1413394908455760384
1413394908505760512
1413394908555760384
1413394908605760512
1413394908655760384
1413394908705760512
1413394908755760384
1413394908805760512
1413394908855760384
1413394908905760512
1413394908955760384
1413394909005760512
1413394909055760384
1413394909105760512
1413394909155760384
1413394909205760512
1413394909255760384
1413394909305760512
1413394909355760384
1413394909405760512
1413394909455760384
1413394909505760512
1413394909555760384
1413394909605760512
1413394909655760384
1413394909705760512
1413394909755760384
1413394909805760512
1413394909855760384
1413394909905760512
1413394909955760384
1413394910005760512
1413394910055760384
1413394910105760512
1413394910155760384
1413394910205760512
1413394910255760384
1413394910305760512
1413394910355760384
1413394910405760512
1413394910455760384
1413394910505760512
1413394910555760384
1413394910605760512
1413394910655760384
1413394910705760512
1413394910755760384
1413394910805760512
1413394910855760384
1413394910905760512
1413394910955760384
1413394911005760512
1413394911055760384
1413394911105760512
1413394911155760384
1413394911205760512
1413394911255760384
1413394911305760512
1413394911355760384
1413394911405760512
1413394911455760384
1413394911505760512
1413394911555760384
1413394911605760512
1413394911655760384
1413394911705760512
1413394911755760384
1413394911805760512
1413394911855760384
1413394911905760512
1413394911955760384
1413394912005760512
1413394912055760384
1413394912105760512
1413394912155760384
1413394912205760512
1413394912255760384
1413394912305760512
1413394912355760384
1413394912405760512
1413394912455760384
1413394912505760512
1413394912555760384
1413394912605760512
1413394912655760384
1413394912705760512
1413394912755760384
1413394912805760512
1413394912855760384
1413394912905760512
1413394912955760384
1413394913005760512
1413394913055760384
1413394913105760512
1413394913155760384
1413394913205760512
1413394913255760384
1413394913305760512
1413394913355760384
1413394913405760512
1413394913455760384
1413394913505760512
1413394913555760384
1413394913605760512
1413394913655760384
1413394913705760512
1413394913755760384
1413394913805760512
1413394913855760384
1413394913905760512
1413394913955760384
1413394914005760512
1413394914055760384
1413394914105760512
1413394914155760384
1413394914205760512
1413394914255760384
1413394914305760512
1413394914355760384
1413394914405760512
1413394914455760384
1413394914505760512
1413394914555760384
1413394914605760512
1413394914655760384
1413394914705760512
1413394914755760384
1413394914805760512
1413394914855760384
1413394914905760512
1413394914955760384
1413394915005760512
1413394915055760384
1413394915105760512
1413394915155760384
1413394915205760512
1413394915255760384
1413394915305760512
1413394915355760384
1413394915405760512
1413394915455760384
1413394915505760512
1413394915555760384
1413394915605760512
1413394915655760384
1413394915705760512
1413394915755760384
1413394915805760512
1413394915855760384
1413394915905760512
1413394915955760384
1413394916005760512
1413394916055760384
1413394916105760512
1413394916155760384
1413394916205760512
1413394916255760384
1413394916305760512
1413394916355760384
1413394916405760512
1413394916455760384
1413394916505760512
1413394916555760384
1413394916605760512
1413394916655760384
1413394916705760512
1413394916755760384
1413394916855760384
1413394916955760384
1413394917055760384
1413394917155760384
1413394917255760384
1413394917355760384
1413394917455760384
1413394917555760384
1413394917655760384
1413394917755760384
1413394917855760384
1413394917955760384
1413394918055760384
1413394918155760384
1413394918255760384
1413394918355760384
1413394918455760384
1413394918555760384
1413394918655760384
1413394918755760384
1413394918855760384
1413394918955760384
1413394919055760384
1413394919155760384
1413394919255760384
1413394919355760384
1413394919455760384
1413394919555760384
1413394919655760384
1413394919755760384
1413394919855760384
1413394919955760384
1413394920055760384
1413394920155760384
1413394920255760384
1413394920355760384
1413394920455760384
1413394920555760384
1413394920655760384
1413394920755760384
1413394920855760384
1413394920955760384
1413394921055760384
1413394921155760384
1413394921255760384
1413394921355760384
1413394921455760384
1413394921555760384
1413394921655760384
1413394921755760384
1413394921855760384
1413394921955760384
1413394922055760384
1413394922155760384
1413394922255760384
1413394922355760384
1413394922455760384
1413394922555760384
1413394922655760384
1413394922755760384
1413394922855760384
1413394922955760384
1413394923055760384
1413394923155760384
1413394923255760384
1413394923355760384
1413394923455760384
1413394923555760384
1413394923655760384
1413394923755760384
1413394923855760384
1413394923955760384
1413394924055760384
1413394924155760384
1413394924255760384
1413394924355760384
1413394924455760384
1413394924555760384
1413394924655760384
1413394924755760384
1413394924855760384
1413394924905760512
1413394924955760384
1413394925005760512
1413394925055760384
1413394925105760512
1413394925155760384
1413394925205760512
1413394925255760384
1413394925305760512
1413394925355760384
1413394925405760512
1413394925455760384
1413394925505760512
1413394925555760384
1413394925605760512
1413394925655760384
1413394925705760512
1413394925755760384
1413394925805760512
1413394925855760384
1413394925905760512
1413394925955760384
1413394926005760512
1413394926055760384
1413394926105760512
1413394926155760384
1413394926205760512
1413394926255760384
1413394926305760512
1413394926355760384
1413394926405760512
1413394926455760384
1413394926505760512
1413394926555760384
1413394926605760512
1413394926655760384
1413394926705760512
1413394926755760384
1413394926805760512
1413394926855760384
1413394926905760512
1413394926955760384
1413394927005760512
1413394927055760384
1413394927105760512
1413394927155760384
1413394927205760512
1413394927255760384
1413394927305760512
1413394927355760384
1413394927405760512
1413394927455760384
1413394927505760512
1413394927555760384
1413394927605760512
1413394927655760384
1413394927705760512
1413394927755760384
1413394927805760512
1413394927855760384
1413394927905760512
1413394927955760384
1413394928005760512
1413394928055760384
1413394928105760512
1413394928155760384
1413394928205760512
1413394928255760384
1413394928305760512
1413394928355760384
1413394928405760512
1413394928455760384
1413394928505760512
1413394928555760384
1413394928605760512
1413394928655760384
1413394928705760512
1413394928755760384
1413394928805760512
1413394928855760384
1413394928905760512
1413394928955760384
1413394929005760512
1413394929055760384
1413394929105760512
1413394929155760384
1413394929205760512
1413394929255760384
1413394929305760512
1413394929355760384
1413394929405760512
1413394929455760384
1413394929505760512
1413394929555760384
1413394929605760512
1413394929655760384
1413394929705760512
1413394929755760384
1413394929805760512
1413394929855760384
1413394929905760512
1413394929955760384
1413394930005760512
1413394930055760384
1413394930105760512
1413394930155760384
1413394930205760512
1413394930255760384
1413394930305760512
1413394930355760384
1413394930405760512
1413394930455760384
1413394930505760512
1413394930555760384
1413394930605760512
1413394930655760384
1413394930705760512
1413394930755760384
1413394930805760512
1413394930855760384
1413394930905760512
1413394930955760384
1413394931005760512
1413394931055760384
1413394931105760512
1413394931155760384
1413394931205760512
1413394931255760384
1413394931305760512
1413394931355760384
1413394931405760512
1413394931455760384
1413394931505760512
1413394931555760384
1413394931605760512
1413394931655760384
1413394931705760512
1413394931755760384
1413394931805760512
1413394931855760384
1413394931905760512
1413394931955760384
1413394932005760512
1413394932055760384
1413394932105760512
1413394932155760384
1413394932205760512
1413394932255760384
1413394932305760512
1413394932355760384
1413394932405760512
1413394932455760384
1413394932505760512
1413394932555760384
1413394932605760512
1413394932655760384
1413394932705760512
1413394932755760384
1413394932805760512
1413394932855760384
1413394932905760512
1413394932955760384
1413394933005760512
1413394933055760384
1413394933105760512
1413394933155760384
1413394933205760512
1413394933255760384
1413394933305760512
1413394933355760384
1413394933405760512
1413394933455760384
1413394933505760512
1413394933555760384
1413394933605760512
1413394933655760384
1413394933705760512
1413394933755760384
1413394933805760512
1413394933855760384
1413394933905760512
1413394933955760384
1413394934005760512
1413394934055760384
1413394934105760512
1413394934155760384
1413394934205760512
1413394934255760384
1413394934305760512
1413394934355760384
1413394934405760512
1413394934455760384
1413394934505760512
1413394934555760384
1413394934605760512
1413394934655760384
1413394934705760512
1413394934755760384
1413394934805760512
1413394934855760384
1413394934905760512
1413394934955760384
1413394935005760512
1413394935055760384
1413394935105760512
1413394935155760384
1413394935205760512
1413394935255760384
1413394935305760512
1413394935355760384
1413394935405760512
1413394935455760384
1413394935505760512
1413394935555760384
1413394935605760512
1413394935655760384
1413394935705760512
1413394935755760384
1413394935805760512
1413394935855760384
1413394935905760512
1413394935955760384
1413394936005760512
1413394936055760384
1413394936105760512
1413394936205760512
1413394936255760384
1413394936305760512
1413394936405760512
1413394936505760512
1413394936605760512
1413394936705760512
1413394936805760512
1413394936905760512
1413394937005760512
1413394937105760512
1413394937205760512
1413394937255760384
1413394937305760512
1413394937355760384
1413394937455760384
1413394937555760384
1413394937655760384
1413394937755760384
1413394937855760384
1413394937955760384
1413394938055760384
1413394938155760384
1413394938255760384
1413394938355760384
1413394938455760384
1413394938555760384
1413394938655760384
1413394938755760384
1413394938855760384
1413394938955760384
1413394939055760384
1413394939155760384
1413394939255760384
1413394939355760384
1413394939455760384
1413394939555760384
1413394939655760384
1413394939755760384
1413394939855760384
1413394939955760384
1413394940055760384
1413394940155760384
1413394940255760384
1413394940355760384
1413394940455760384
1413394940555760384
1413394940655760384
1413394940755760384
1413394940855760384
1413394940955760384
1413394941005760512
1413394941055760384
1413394941105760512
1413394941205760512
1413394941305760512
1413394941405760512
1413394941505760512
1413394941605760512
1413394941705760512
1413394941755760384
1413394941805760512
1413394941855760384
1413394941905760512
1413394941955760384
1413394942005760512
1413394942055760384
1413394942105760512
1413394942155760384
1413394942205760512
1413394942255760384
1413394942305760512
1413394942355760384
1413394942405760512
1413394942455760384
1413394942505760512
1413394942555760384
1413394942605760512
1413394942655760384
1413394942705760512
1413394942755760384
1413394942805760512
1413394942855760384
1413394942905760512
1413394942955760384
1413394943005760512
1413394943055760384
1413394943105760512
1413394943155760384
1413394943205760512
1413394943255760384
1413394943305760512
1413394943355760384
1413394943405760512
1413394943455760384
1413394943505760512
1413394943555760384
1413394943605760512
1413394943655760384
1413394943705760512
1413394943755760384
1413394943805760512
1413394943855760384
1413394943905760512
1413394943955760384
1413394944005760512
1413394944055760384
1413394944105760512
1413394944155760384
1413394944205760512
1413394944255760384
1413394944305760512
1413394944355760384
1413394944405760512
1413394944455760384
1413394944505760512
1413394944555760384
1413394944605760512
1413394944655760384
1413394944705760512
1413394944755760384
1413394944805760512
1413394944855760384
1413394944905760512
1413394944955760384
1413394945005760512
1413394945055760384
1413394945105760512
1413394945155760384
1413394945205760512
1413394945255760384
1413394945305760512
1413394945355760384
1413394945405760512
1413394945455760384
1413394945505760512
1413394945555760384
1413394945605760512
1413394945655760384
1413394945705760512
1413394945755760384
1413394945805760512
1413394945855760384
1413394945905760512
1413394945955760384
1413394946005760512
1413394946055760384
1413394946155760384
1413394946205760512
1413394946255760384
1413394946355760384
1413394946455760384
1413394946555760384
1413394946655760384
1413394946755760384
1413394946855760384
1413394946955760384
1413394947055760384
1413394947155760384
1413394947255760384
1413394947355760384
1413394947455760384
1413394947555760384
1413394947655760384
1413394947755760384
1413394947855760384
1413394947955760384
1413394948055760384
1413394948155760384
1413394948255760384
1413394948355760384
1413394948455760384
1413394948555760384
1413394948655760384
1413394948755760384
1413394948855760384
1413394948955760384
1413394949055760384
1413394949155760384
1413394949255760384
1413394949355760384
1413394949455760384
1413394949555760384
1413394949655760384
1413394949755760384
1413394949855760384
1413394949955760384
1413394950055760384
1413394950155760384
1413394950255760384
1413394950355760384
1413394950455760384
1413394950555760384
1413394950655760384
1413394950755760384
1413394950855760384
1413394950955760384
1413394951055760384
1413394951155760384
1413394951255760384
1413394951355760384
1413394951455760384
1413394951555760384
1413394951655760384
1413394951755760384
1413394951855760384
1413394951955760384
1413394952055760384
1413394952155760384
1413394952255760384
1413394952355760384
1413394952455760384
1413394952555760384
1413394952655760384
1413394952755760384
1413394952855760384
1413394952955760384
1413394953055760384
1413394953155760384
1413394953255760384
1413394953355760384
1413394953455760384
1413394953555760384
1413394953655760384
1413394953755760384
1413394953855760384
1413394953955760384
1413394954055760384
1413394954155760384
1413394954255760384
1413394954355760384
1413394954455760384
1413394954555760384
1413394954655760384
1413394954755760384
1413394954855760384
1413394954955760384
1413394955055760384
1413394955155760384
1413394955255760384
1413394955355760384
1413394955455760384
1413394955555760384
1413394955655760384
1413394955755760384
1413394955855760384
1413394955905760512
1413394955955760384
1413394956005760512
1413394956105760512
1413394956205760512
1413394956305760512
1413394956405760512
1413394956505760512
1413394956605760512
1413394956655760384
1413394956705760512
1413394956755760384
1413394956805760512
1413394956855760384
1413394956905760512
1413394956955760384
1413394957005760512
1413394957055760384
1413394957105760512
1413394957155760384
1413394957205760512
1413394957255760384
1413394957305760512
1413394957355760384
1413394957405760512
1413394957455760384
1413394957505760512
1413394957555760384
1413394957605760512
1413394957655760384
1413394957705760512
1413394957755760384
1413394957805760512
1413394957855760384
1413394957905760512
1413394957955760384
1413394958005760512
1413394958055760384
1413394958105760512
1413394958155760384
1413394958205760512
1413394958255760384
1413394958305760512
1413394958355760384
1413394958405760512
1413394958455760384
1413394958505760512
1413394958555760384
1413394958605760512
1413394958655760384
1413394958705760512
1413394958755760384
1413394958805760512
1413394958855760384
1413394958905760512
1413394958955760384
1413394959005760512
1413394959055760384
1413394959105760512
1413394959155760384
1413394959205760512
1413394959255760384
1413394959305760512
1413394959355760384
1413394959405760512
1413394959455760384
1413394959505760512
1413394959555760384
1413394959605760512
1413394959655760384
1413394959705760512
1413394959755760384
1413394959805760512
1413394959855760384
1413394959905760512
1413394959955760384
1413394960005760512
1413394960055760384
1413394960105760512
1413394960155760384
1413394960205760512
1413394960255760384
1413394960305760512
1413394960355760384
1413394960405760512
1413394960455760384
1413394960505760512
1413394960555760384
1413394960605760512
1413394960655760384
1413394960705760512
1413394960755760384
1413394960805760512
1413394960855760384
1413394960905760512
1413394960955760384
1413394961005760512
1413394961055760384
1413394961105760512
1413394961155760384
1413394961205760512
1413394961255760384
1413394961305760512
1413394961355760384
1413394961405760512
1413394961455760384
1413394961505760512
1413394961555760384
1413394961605760512
1413394961655760384
1413394961705760512
1413394961755760384
1413394961805760512
1413394961855760384
1413394961905760512
1413394961955760384
1413394962005760512
1413394962055760384
1413394962105760512
1413394962155760384
1413394962205760512
1413394962255760384
1413394962305760512
1413394962355760384
1413394962405760512
1413394962455760384
1413394962505760512
1413394962555760384
1413394962605760512
1413394962655760384
1413394962705760512
1413394962755760384
1413394962805760512
1413394962855760384
1413394962905760512
1413394962955760384
1413394963005760512
1413394963055760384
1413394963105760512
1413394963155760384
1413394963205760512
1413394963255760384
1413394963305760512
1413394963355760384
1413394963405760512
1413394963455760384
1413394963505760512
1413394963555760384
1413394963605760512
1413394963655760384
1413394963705760512
1413394963755760384
1413394963805760512
1413394963855760384
1413394963905760512
1413394963955760384
1413394964005760512
1413394964055760384
1413394964105760512
1413394964155760384
1413394964205760512
1413394964255760384
1413394964305760512
1413394964355760384
1413394964405760512
1413394964455760384
1413394964505760512
1413394964555760384
1413394964605760512
1413394964655760384
1413394964705760512
1413394964755760384
1413394964805760512
1413394964855760384
1413394964905760512
1413394964955760384
1413394965005760512
1413394965055760384
1413394965105760512
1413394965155760384
1413394965205760512
1413394965255760384
1413394965305760512
1413394965355760384
1413394965405760512
1413394965455760384
1413394965505760512
1413394965555760384
1413394965605760512
1413394965655760384
1413394965705760512
1413394965755760384
1413394965805760512
1413394965855760384
1413394965905760512
1413394965955760384
1413394966005760512
1413394966055760384
1413394966105760512
1413394966155760384
1413394966205760512
1413394966255760384
1413394966305760512
1413394966355760384
1413394966405760512
1413394966455760384
1413394966505760512
1413394966555760384
1413394966605760512
1413394966655760384
1413394966705760512
1413394966755760384
1413394966805760512
1413394966855760384
1413394966905760512
1413394966955760384
1413394967005760512
1413394967055760384
1413394967105760512
1413394967155760384
1413394967205760512
1413394967255760384
1413394967305760512
1413394967355760384
1413394967405760512
1413394967455760384
1413394967505760512
1413394967555760384
1413394967605760512
1413394967655760384
1413394967705760512
1413394967755760384
1413394967805760512
1413394967855760384
1413394967905760512
1413394967955760384
1413394968005760512
1413394968055760384
1413394968105760512
1413394968155760384
1413394968205760512
1413394968255760384
1413394968305760512
1413394968355760384
1413394968405760512
1413394968455760384
1413394968505760512
1413394968555760384
1413394968605760512
1413394968655760384
1413394968705760512
1413394968755760384
1413394968805760512
1413394968855760384
1413394968905760512
1413394968955760384
1413394969005760512
1413394969055760384
1413394969155760384
1413394969255760384
1413394969355760384
1413394969455760384
1413394969555760384
1413394969655760384
1413394969755760384
1413394969855760384
1413394969955760384
1413394970055760384
1413394970155760384
1413394970255760384
1413394970355760384
1413394970455760384
1413394970555760384
1413394970655760384
1413394970755760384
1413394970855760384
1413394970955760384
1413394971055760384
1413394971155760384
1413394971255760384
1413394971355760384
1413394971455760384
1413394971555760384
1413394971655760384
1413394971755760384
1413394971855760384
1413394971955760384
1413394972055760384
1413394972155760384
1413394972255760384
1413394972355760384
1413394972455760384
1413394972555760384
1413394972655760384
1413394972755760384
1413394972855760384
1413394972955760384
1413394973005760512
1413394973055760384
1413394973105760512
1413394973155760384
1413394973205760512
1413394973255760384
1413394973305760512
1413394973355760384
1413394973405760512
1413394973455760384
1413394973505760512
1413394973555760384
1413394973605760512
1413394973655760384
1413394973705760512
1413394973755760384
1413394973805760512
1413394973855760384
1413394973905760512
1413394973955760384
1413394974005760512
1413394974055760384
1413394974105760512
1413394974155760384
1413394974205760512
1413394974255760384
1413394974305760512
1413394974355760384
1413394974405760512
1413394974455760384
1413394974505760512
1413394974555760384
1413394974605760512
1413394974655760384
1413394974705760512
1413394974755760384
1413394974805760512
1413394974855760384
1413394974905760512
1413394974955760384
1413394975005760512
1413394975055760384
1413394975105760512
1413394975155760384
1413394975205760512
1413394975255760384
1413394975305760512
1413394975355760384
1413394975405760512
1413394975455760384
1413394975505760512
1413394975555760384
1413394975605760512
1413394975655760384
1413394975755760384
1413394975805760512
1413394975855760384
1413394975955760384
1413394976055760384
1413394976155760384
1413394976255760384
1413394976355760384
1413394976455760384
1413394976505760512
1413394976605760512
1413394976705760512
1413394976755760384
1413394976805760512
1413394976855760384
1413394976905760512
1413394976955760384
1413394977005760512
1413394977105760512
1413394977155760384
1413394977205760512
1413394977305760512
1413394977405760512
1413394977505760512
1413394977605760512
1413394977705760512
1413394977805760512
1413394977905760512
1413394978005760512
1413394978105760512
1413394978155760384
1413394978205760512
1413394978255760384
1413394978305760512
1413394978355760384
1413394978405760512
1413394978455760384
1413394978505760512
1413394978555760384
1413394978605760512
1413394978655760384
1413394978705760512
1413394978755760384
1413394978805760512
1413394978855760384
1413394978905760512
1413394978955760384
1413394979005760512
1413394979055760384
1413394979105760512
1413394979155760384
1413394979205760512
1413394979255760384
1413394979305760512
1413394979355760384
1413394979405760512
1413394979455760384
1413394979505760512
1413394979555760384
1413394979605760512
1413394979655760384
1413394979705760512
1413394979755760384
1413394979805760512
1413394979855760384
1413394979905760512
1413394979955760384
1413394980005760512
1413394980055760384
1413394980105760512
1413394980155760384
1413394980205760512
1413394980255760384
1413394980305760512
1413394980355760384
1413394980405760512
1413394980455760384
1413394980505760512
1413394980555760384
1413394980605760512
1413394980655760384
1413394980705760512
1413394980755760384
1413394980805760512
1413394980855760384
1413394980905760512
1413394980955760384
1413394981005760512
1413394981055760384
1413394981105760512
1413394981155760384
1413394981205760512
1413394981255760384
1413394981305760512
1413394981355760384
1413394981405760512
1413394981455760384
1413394981505760512
1413394981555760384
1413394981605760512
1413394981655760384
1413394981705760512
1413394981755760384
1413394981805760512
1413394981855760384
1413394981905760512
1413394981955760384
1413394982005760512
1413394982055760384
1413394982105760512
1413394982155760384
1413394982205760512
1413394982255760384
1413394982305760512
1413394982355760384
1413394982405760512
1413394982455760384
1413394982505760512
1413394982555760384
1413394982605760512
1413394982655760384
1413394982705760512
1413394982755760384
1413394982805760512
1413394982855760384
1413394982905760512
1413394983005760512
1413394983105760512
1413394983205760512
1413394983305760512
1413394983405760512
1413394983505760512
1413394983605760512
1413394983705760512
1413394983805760512
1413394983905760512
1413394984005760512
1413394984105760512
1413394984205760512
1413394984305760512
1413394984405760512
1413394984505760512
1413394984605760512
1413394984705760512
1413394984805760512
1413394984905760512
1413394985005760512
1413394985105760512
1413394985205760512
1413394985305760512
1413394985405760512
1413394985505760512
1413394985605760512
1413394985705760512
1413394985805760512
1413394985905760512
1413394986005760512
1413394986105760512
1413394986205760512
1413394986305760512
1413394986405760512
1413394986505760512
1413394986605760512
1413394986705760512
1413394986805760512
1413394986905760512
1413394987005760512
1413394987105760512
1413394987205760512
1413394987305760512
1413394987405760512
1413394987505760512
1413394987605760512
1413394987705760512
1413394987805760512
1413394987905760512
1413394988005760512
1413394988105760512
1413394988205760512
1413394988305760512
1413394988405760512
1413394988505760512
1413394988605760512
1413394988705760512
1413394988805760512
1413394988905760512
1413394989005760512
1413394989105760512
1413394989205760512
1413394989305760512
1413394989405760512
1413394989505760512
1413394989605760512
1413394989705760512
1413394989805760512
1413394989905760512
1413394990005760512
1413394990105760512
1413394990155760384
1413394990205760512
1413394990255760384
1413394990355760384
1413394990405760512
1413394990455760384
1413394990505760512
1413394990555760384
1413394990605760512
1413394990655760384
1413394990705760512
1413394990755760384
1413394990805760512
1413394990855760384
1413394990905760512
1413394990955760384
1413394991005760512
1413394991055760384
1413394991105760512
1413394991155760384
1413394991205760512
1413394991255760384
1413394991305760512
1413394991355760384
1413394991405760512
1413394991455760384
1413394991505760512
1413394991555760384
1413394991605760512
1413394991655760384
1413394991705760512
1413394991755760384
1413394991805760512
1413394991855760384
1413394991905760512
1413394991955760384
1413394992005760512
1413394992055760384
1413394992105760512
1413394992155760384
1413394992205760512
1413394992255760384
1413394992305760512
1413394992355760384
1413394992405760512
1413394992455760384
1413394992505760512
1413394992555760384
1413394992605760512
1413394992655760384
1413394992705760512
1413394992755760384
1413394992805760512
1413394992855760384
1413394992905760512
1413394992955760384
1413394993005760512
1413394993055760384
1413394993105760512
1413394993155760384
1413394993205760512
1413394993255760384
1413394993305760512
1413394993355760384
1413394993405760512
1413394993455760384
1413394993505760512
1413394993555760384
1413394993605760512
1413394993655760384
1413394993705760512
1413394993755760384
1413394993805760512
1413394993855760384
1413394993905760512
1413394993955760384
1413394994005760512
1413394994055760384
1413394994105760512
1413394994155760384
1413394994205760512
1413394994305760512
1413394994405760512
1413394994505760512
1413394994605760512
1413394994705760512
1413394994805760512
1413394994905760512
1413394995005760512
1413394995105760512
1413394995205760512
1413394995305760512
1413394995405760512
1413394995505760512
1413394995605760512
1413394995705760512
1413394995805760512
1413394995905760512
1413394996005760512
1413394996105760512
1413394996205760512
1413394996305760512
1413394996405760512
1413394996505760512
1413394996605760512
1413394996705760512
1413394996805760512
1413394996905760512
1413394997005760512
1413394997105760512
1413394997205760512
1413394997305760512
1413394997405760512
1413394997505760512
1413394997605760512
1413394997705760512
1413394997805760512
1413394997905760512
1413394998005760512
1413394998105760512
1413394998205760512
1413394998305760512
================================================
FILE: Examples/Stereo/KITTI00-02.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# GPU Parameters
#--------------------------------------------------------------------------------------------
gpu.use_gpu: 1
gpu.is_jetson: 0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 718.856
Camera.fy: 718.856
Camera.cx: 607.1928
Camera.cy: 185.2157
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 1241
Camera.height: 376
# Camera frames per second
Camera.fps: 10.0
# stereo baseline times fx
Camera.bf: 386.1448
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
ORBextractor.tile_h: 25
ORBextractor.tile_w: 25
ORBextractor.fixed_multi_scale_tile_size: 0
ORBextractor.apply_nms_ms: 1
ORBextractor.nms_ms_mode_gpu: 1
ORBextractor.scaleFactor: 1.2
ORBextractor.nLevels: 1
# ORB Extractor: Fast threshold
# Firstly we impose th_FAST_MAX. If no corners are detected we impose a lower value th_FAST_MIN
# You can lower these values if your images have low contrast
ORBextractor.th_FAST_MIN: 7
ORBextractor.th_FAST_MAX: 60
ORBextractor.FAST_N_MIN: 9
ORBextractor.FAST_N_MAX: 14
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.6
Viewer.KeyFrameLineWidth: 2
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -100
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 500
================================================
FILE: Examples/Stereo/KITTI00-02_custom.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 315.856
Camera.fy: 315.856
Camera.cx: 320.1928
Camera.cy: 240.2157
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30.0
# stereo baseline times fx
Camera.bf: 25.2
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 2000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.6
Viewer.KeyFrameLineWidth: 2
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -100
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Stereo/KITTI03.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 721.5377
Camera.fy: 721.5377
Camera.cx: 609.5593
Camera.cy: 172.854
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 1241
Camera.height: 376
# Camera frames per second
Camera.fps: 10.0
# stereo baseline times fx
Camera.bf: 387.5744
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 2000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.6
Viewer.KeyFrameLineWidth: 2
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -100
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Stereo/KITTI04-12.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# GPU Parameters
#--------------------------------------------------------------------------------------------
gpu.use_gpu: 1
gpu.is_jetson: 0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 707.0912
Camera.fy: 707.0912
Camera.cx: 601.8873
Camera.cy: 183.1104
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 1226
Camera.height: 370
# Camera frames per second
Camera.fps: 10.0
# stereo baseline times fx
Camera.bf: 379.8145
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
ORBextractor.tile_h: 30
ORBextractor.tile_w: 30
ORBextractor.fixed_multi_scale_tile_size: 0
ORBextractor.apply_nms_ms: 1
ORBextractor.nms_ms_mode_gpu: 1
ORBextractor.scaleFactor: 1.2
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Firstly we impose th_FAST_MAX. If no corners are detected we impose a lower value th_FAST_MIN
# You can lower these values if your images have low contrast
ORBextractor.th_FAST_MIN: 7
ORBextractor.th_FAST_MAX: 40
ORBextractor.FAST_N_MIN: 9
ORBextractor.FAST_N_MAX: 14
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 12
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.6
Viewer.KeyFrameLineWidth: 2
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -100
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Stereo/euroc_old/CameraTrajectory_MH01.txt
================================================
1403636579763555584 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 1.000000000
1403636579813555456 0.000626662 0.014715765 0.006955123 0.001351663 0.002597654 -0.000358683 0.999995649
1403636579863555584 0.000679460 0.033276867 0.013114153 -0.000907021 0.004789774 -0.002263839 0.999985576
1403636579913555456 0.000311744 0.055236425 0.019478306 -0.005933005 0.005779623 -0.002855460 0.999961615
1403636579963555584 -0.000381168 0.078955710 0.026695568 -0.012271425 0.005617524 -0.002635309 0.999905467
1403636580013555456 -0.000675092 0.104272567 0.033921383 -0.017137317 0.005488157 -0.000710915 0.999837816
1403636580063555584 -0.001292706 0.130759925 0.041463576 -0.020948200 0.005794617 -0.000069949 0.999763787
1403636580113555456 -0.001948377 0.154691547 0.047665421 -0.023472790 0.005267345 0.002316567 0.999707937
1403636580163555584 -0.002841459 0.179985672 0.054671418 -0.025423840 0.005116343 0.003453195 0.999657691
1403636580213555456 -0.003787125 0.204055116 0.061365552 -0.027465412 0.004875424 0.003034237 0.999606252
1403636580263555584 -0.004207271 0.224479914 0.065790303 -0.030342458 0.004792551 0.003058946 0.999523401
1403636580313555456 -0.004990415 0.245213777 0.070488140 -0.033887301 0.004739442 0.000671006 0.999414206
1403636580363555584 -0.005436008 0.263729900 0.073317744 -0.039925657 0.003542898 0.000052464 0.999196351
1403636580413555456 -0.005898318 0.279083401 0.077165924 -0.047517397 0.003433340 -0.000903309 0.998864114
1403636580463555584 -0.007027687 0.292013735 0.077564448 -0.056436162 0.003164925 -0.001949623 0.998399317
1403636580513555456 -0.008207255 0.298749596 0.077514388 -0.065105729 0.002904062 -0.002136706 0.997871876
1403636580563555584 -0.008699704 0.297386646 0.076248586 -0.071551859 0.001579840 -0.000609500 0.997435451
1403636580613555456 -0.008887449 0.288002163 0.074047804 -0.073930413 0.000085617 -0.000930917 0.997263014
1403636580663555584 -0.010597291 0.268722624 0.067321137 -0.072746150 0.000347907 -0.000125991 0.997350395
1403636580713555456 -0.011561003 0.243574485 0.061627455 -0.069061942 0.001769683 -0.002419388 0.997607887
1403636580763555584 -0.011648604 0.212575808 0.053782966 -0.063329317 0.003934146 -0.005876512 0.997967601
1403636580813555456 -0.012005555 0.177799225 0.047420174 -0.056574915 0.006890736 -0.008129562 0.998341441
1403636580863555584 -0.012609146 0.139472649 0.039117403 -0.049164683 0.012325791 -0.012556387 0.998635709
1403636580913555456 -0.012684166 0.101109847 0.031851009 -0.041339546 0.017311256 -0.015617347 0.998873055
1403636580963555584 -0.014170120 0.061881717 0.023069592 -0.033768371 0.019720348 -0.017756129 0.999077320
1403636581013555456 -0.015335118 0.027058892 0.015771013 -0.026746375 0.019661346 -0.018898107 0.999270201
1403636581063555584 -0.018007463 -0.008924683 0.008426530 -0.020447686 0.019344388 -0.019475071 0.999413967
1403636581113555456 -0.019174803 -0.040325060 0.000083638 -0.013698484 0.019799406 -0.018527228 0.999538422
1403636581163555584 -0.019969404 -0.068843566 -0.005642319 -0.005611136 0.020425260 -0.015141953 0.999660969
1403636581213555456 -0.019160708 -0.093023725 -0.010388447 0.002598180 0.020806534 -0.013357522 0.999690890
1403636581263555584 -0.019430548 -0.116760157 -0.017961651 0.011181443 0.020761149 -0.010656026 0.999665141
1403636581313555456 -0.018982280 -0.131783485 -0.024833580 0.018938262 0.020655876 -0.011771502 0.999537945
1403636581363555584 -0.017648822 -0.141352579 -0.028758839 0.023904240 0.020970905 -0.011744988 0.999425292
1403636581413555456 -0.017536655 -0.141280651 -0.029545920 0.025142811 0.023474127 -0.014024550 0.999309838
1403636581463555584 -0.015194610 -0.132581607 -0.027576514 0.022841459 0.024574695 -0.017052755 0.999291539
1403636581513555456 -0.014001097 -0.115232609 -0.026488181 0.017543402 0.025874725 -0.019442962 0.999322116
1403636581563555584 -0.011625872 -0.092245497 -0.019894395 0.011438081 0.026381219 -0.018190825 0.999421000
1403636581613555456 -0.009297360 -0.064837962 -0.010229793 0.004844970 0.025383066 -0.017163532 0.999518752
1403636581663555584 -0.009065819 -0.035429534 -0.001394003 -0.000322111 0.025002914 -0.015120246 0.999572992
1403636581713555456 -0.005415183 -0.003925988 0.007163212 -0.003920443 0.024074377 -0.016732203 0.999562442
1403636581763555584 -0.003469858 0.027350232 0.016142283 -0.005743474 0.022769189 -0.014975098 0.999612093
1403636581813555456 -0.001601903 0.061034273 0.023975644 -0.007093818 0.019697744 -0.015052163 0.999667466
1403636581863555584 -0.000173048 0.093858667 0.031698637 -0.009394376 0.018583762 -0.014408731 0.999679267
1403636581913555456 0.000285506 0.127112895 0.038888127 -0.014211266 0.016909899 -0.012312046 0.999680221
1403636581963555584 0.000530468 0.159873039 0.046421796 -0.020983890 0.018994585 -0.010397755 0.999545336
1403636582013555456 0.001034854 0.188442260 0.054381747 -0.029130138 0.020702789 -0.008392273 0.999326050
1403636582063555584 0.000955808 0.215439439 0.060144246 -0.037910417 0.022441767 -0.008733500 0.998991013
1403636582113555456 0.000658795 0.236699760 0.064947069 -0.046316959 0.022012897 -0.009629006 0.998637795
1403636582163555584 -0.000973915 0.251804858 0.067039818 -0.053796798 0.020448688 -0.009825219 0.998294175
1403636582213555456 -0.002824391 0.260810256 0.067953475 -0.059842736 0.018907541 -0.010275537 0.997975826
1403636582263555584 -0.003609092 0.259498984 0.067208290 -0.063232131 0.017396763 -0.009538755 0.997801602
1403636582313555456 -0.005769581 0.250795454 0.065122247 -0.064486563 0.016540056 -0.010827600 0.997722745
1403636582363555584 -0.008225298 0.232770026 0.061058298 -0.061792757 0.015485829 -0.009764914 0.997921050
1403636582413555456 -0.010061234 0.208973169 0.055682249 -0.054865759 0.015017498 -0.009339374 0.998337090
1403636582463555584 -0.011770755 0.180491120 0.047943462 -0.047196764 0.014864538 -0.009103302 0.998733521
1403636582513555456 -0.013052311 0.149954513 0.040424872 -0.040838949 0.016354594 -0.011149876 0.998969674
1403636582563555584 -0.014220554 0.118998297 0.033602312 -0.035585392 0.017961420 -0.010928248 0.999145508
1403636582613555456 -0.013890719 0.084221050 0.024748899 -0.032623120 0.020783093 -0.013739567 0.999157131
1403636582663555584 -0.014964666 0.052826095 0.016059166 -0.030025830 0.023708209 -0.013876763 0.999171555
1403636582713555456 -0.013910029 0.020141205 0.008106720 -0.027795967 0.024934322 -0.013585281 0.999210238
1403636582763555584 -0.013419173 -0.012457505 0.000974140 -0.024446027 0.027082972 -0.011667445 0.999266148
1403636582813555456 -0.010991164 -0.044688940 -0.006713663 -0.019576970 0.030116566 -0.008866129 0.999315321
1403636582863555584 -0.009708201 -0.077379473 -0.012959656 -0.012635794 0.034720007 -0.006894128 0.999293447
1403636582913555456 -0.007318933 -0.106153116 -0.019799326 -0.004482654 0.037865732 -0.004445682 0.999262869
1403636582963555584 -0.007178749 -0.131897658 -0.027758207 0.003945068 0.039844334 -0.004032926 0.999189973
1403636583013555456 -0.005571218 -0.151297688 -0.033171460 0.012406935 0.041687597 -0.003789991 0.999046445
1403636583063555584 -0.004282196 -0.163169920 -0.037856311 0.017881807 0.041470487 -0.004734112 0.998968482
1403636583113555456 -0.004645316 -0.171169207 -0.042293992 0.019935736 0.042742394 -0.005938525 0.998869538
1403636583163555584 -0.002224121 -0.168209463 -0.040754251 0.020226289 0.044616267 -0.008280482 0.998765111
1403636583213555456 -0.002748876 -0.158145472 -0.037248649 0.018648963 0.045267463 -0.010313208 0.998747587
1403636583263555584 -0.002204869 -0.139259949 -0.032390162 0.016946755 0.044510193 -0.011207704 0.998802304
1403636583313555456 -0.000759437 -0.118074805 -0.024801355 0.014959576 0.043426134 -0.011167765 0.998882234
1403636583363555584 0.001177167 -0.093086489 -0.016318100 0.012240889 0.042611562 -0.012178214 0.998942494
1403636583413555456 0.005639223 -0.062015083 -0.003707227 0.010295266 0.039853279 -0.010608161 0.999096215
1403636583463555584 0.005193897 -0.030449731 0.001192758 0.006787049 0.038049173 -0.012829200 0.999170482
1403636583513555456 0.008167950 0.003235920 0.011890182 0.003719871 0.036323328 -0.013513499 0.999241769
1403636583563555584 0.010020599 0.037084609 0.021529362 -0.000824002 0.036014929 -0.015225237 0.999234915
1403636583613555456 0.013068464 0.071818218 0.031526823 -0.006466615 0.038239487 -0.016824195 0.999106050
1403636583663555584 0.013228664 0.105616555 0.040367547 -0.014969121 0.035254158 -0.014929925 0.999154747
1403636583713555456 0.013328178 0.138905242 0.048476811 -0.025273575 0.033612449 -0.011035061 0.999054372
1403636583763555584 0.013963642 0.168800712 0.055641059 -0.036892764 0.031553775 -0.006806730 0.998797774
1403636583813555456 0.014075547 0.195267946 0.062270727 -0.047157083 0.031386148 -0.004254804 0.998385191
1403636583863555584 0.014859542 0.219768003 0.066618323 -0.054755382 0.031378508 -0.003916681 0.997999012
1403636583913555456 0.014988445 0.242452294 0.071909517 -0.060456671 0.031978533 -0.007408197 0.997630954
1403636583963555584 0.015178960 0.259175539 0.074033424 -0.063583128 0.030248417 -0.010064380 0.997467279
1403636584013555456 0.014769127 0.270541787 0.075436749 -0.064904593 0.026863240 -0.010586916 0.997473598
1403636584063555584 0.012937238 0.275651872 0.074877888 -0.064943306 0.023250973 -0.011906282 0.997546971
1403636584113555456 0.010857424 0.272957474 0.072258621 -0.064800121 0.020756742 -0.012053636 0.997609556
1403636584163555584 0.010222675 0.263598561 0.071079552 -0.064896256 0.018223714 -0.012044151 0.997652888
1403636584213555456 0.008605720 0.246028766 0.065782346 -0.064760871 0.017590309 -0.012773166 0.997664034
1403636584263555584 0.007055784 0.223960027 0.061494552 -0.063554645 0.017878944 -0.013250699 0.997730196
1403636584313555456 0.005272297 0.197332397 0.055440865 -0.061348867 0.018245326 -0.014214342 0.997848332
1403636584363555584 0.005831542 0.168160036 0.050620608 -0.058999404 0.018812709 -0.014811709 0.997970819
1403636584413555456 0.006236379 0.135203034 0.044430051 -0.057132903 0.022516867 -0.018149948 0.997947574
1403636584463555584 0.006364996 0.099331997 0.038236700 -0.053902380 0.025964860 -0.021526486 0.997976422
1403636584513555456 0.006027162 0.063328050 0.030847594 -0.048787121 0.027736314 -0.021993116 0.998181701
1403636584563555584 0.005901122 0.026942989 0.024433577 -0.042032901 0.029347759 -0.021264032 0.998458683
1403636584613555456 0.004418212 -0.011459031 0.016368490 -0.033245407 0.032184135 -0.021217007 0.998703539
1403636584663555584 0.004001410 -0.047174364 0.010069440 -0.022836896 0.035985980 -0.019649217 0.998898089
1403636584713555456 0.002896733 -0.079597048 0.002458570 -0.011819629 0.039474785 -0.019364433 0.998962998
1403636584763555584 0.002405583 -0.109844588 -0.004234548 -0.001586662 0.043350354 -0.019228002 0.998873651
1403636584813555456 0.001732222 -0.137529626 -0.011181493 0.006716262 0.045080576 -0.018624289 0.998787165
1403636584863555584 0.000609795 -0.160601348 -0.019306486 0.013624605 0.045964438 -0.015929440 0.998723149
1403636584913555456 0.000004601 -0.176187187 -0.023270212 0.018371461 0.045486048 -0.014488158 0.998690963
1403636584963555584 -0.002286812 -0.190235510 -0.028308656 0.020565039 0.046410959 -0.011524244 0.998644233
1403636585013555456 -0.002837581 -0.193223432 -0.032265734 0.020371893 0.048412241 -0.010296074 0.998566628
1403636585063555584 -0.003073357 -0.189769641 -0.029422181 0.018778600 0.050026894 -0.009156139 0.998529315
1403636585113555456 -0.003776673 -0.181186423 -0.026836885 0.016568670 0.050430585 -0.009184078 0.998547912
1403636585163555584 -0.001693269 -0.165416986 -0.021710467 0.013844176 0.052683931 -0.008201737 0.998481572
1403636585213555456 0.001327252 -0.145216912 -0.011564670 0.010809652 0.055330459 -0.008292205 0.998375118
1403636585263555584 0.003325264 -0.123973340 -0.005416804 0.007003602 0.058400948 -0.011206868 0.998205721
1403636585313555456 0.007093822 -0.096570648 0.005444907 0.004455060 0.060678191 -0.014492505 0.998042226
1403636585363555584 0.009292315 -0.070692830 0.012688864 0.000947943 0.062262971 -0.019460544 0.997869551
1403636585413555456 0.012602083 -0.045493644 0.021285757 -0.002710553 0.062163625 -0.021308823 0.997834802
1403636585463555584 0.015041869 -0.018390819 0.029512817 -0.007279637 0.058998663 -0.023118952 0.997963727
1403636585513555456 0.016582895 0.006993357 0.035489749 -0.012869314 0.056334246 -0.024364566 0.998031676
1403636585563555584 0.017327722 0.031202434 0.037710074 -0.018855780 0.050542917 -0.025180398 0.998226345
1403636585613555456 0.018714787 0.053139500 0.036384191 -0.024962259 0.043566458 -0.024725568 0.998432517
1403636585663555584 0.018914219 0.072749369 0.036279060 -0.031560633 0.037432589 -0.022530425 0.998546481
1403636585713555456 0.018574987 0.087258875 0.033665027 -0.039028108 0.030957151 -0.019456437 0.998568952
1403636585763555584 0.018987900 0.098442502 0.030127540 -0.046982668 0.026794489 -0.016048208 0.998407304
1403636585813555456 0.018070601 0.106477983 0.027037220 -0.054743052 0.022446517 -0.012091574 0.998174906
1403636585863555584 0.017384034 0.110374615 0.021153588 -0.064018138 0.018994318 -0.008221019 0.997734070
1403636585913555456 0.016628876 0.112668388 0.016781976 -0.073349699 0.016669579 -0.005220102 0.997153282
1403636585963555584 0.016322259 0.114009671 0.012164950 -0.083816700 0.016921863 -0.002738250 0.996333718
1403636586013555456 0.016533285 0.113431416 0.009211475 -0.096326292 0.020102242 -0.000467393 0.995146692
1403636586063555584 0.017133148 0.113866165 0.006578289 -0.108388096 0.026357209 0.000350149 0.993759096
1403636586113555456 0.015688347 0.111882024 0.003182625 -0.119186744 0.033163179 0.001846751 0.992316127
1403636586163555584 0.013469206 0.110798873 0.000564132 -0.128724620 0.038670264 0.003858493 0.990918636
1403636586213555456 0.010787289 0.108349018 -0.003402600 -0.137875021 0.041105289 0.005925839 0.989578545
1403636586263555584 0.009175025 0.108264983 -0.007443784 -0.147076890 0.041570053 0.007978220 0.988218963
1403636586313555456 0.007179499 0.107286312 -0.013202844 -0.157020077 0.042368233 0.010396082 0.986631393
1403636586363555584 0.006690414 0.106406808 -0.018604839 -0.167584330 0.043206759 0.012998836 0.984824717
1403636586413555456 0.005954123 0.106852129 -0.024093375 -0.178017646 0.043765344 0.016085058 0.982921958
1403636586463555584 0.006917577 0.107956007 -0.030856458 -0.187473685 0.043004364 0.016968189 0.981181085
1403636586513555456 0.007250177 0.109339990 -0.035670973 -0.195693403 0.043859348 0.014933963 0.979570031
1403636586563555584 0.009324486 0.109336108 -0.042793937 -0.201725438 0.042449154 0.015127513 0.978404880
1403636586613555456 0.011991950 0.108075671 -0.046352737 -0.205690309 0.041098934 0.014627566 0.977644324
1403636586663555584 0.017400229 0.105619065 -0.048254553 -0.206482306 0.040190473 0.015620658 0.977499783
1403636586713555456 0.020668734 0.104250416 -0.049390420 -0.203376770 0.040338680 0.015158292 0.978151798
1403636586763555584 0.025641255 0.102533586 -0.048795648 -0.199740902 0.037645269 0.016526928 0.978985846
1403636586813555456 0.030184051 0.100513875 -0.047846079 -0.195373654 0.035987623 0.016655797 0.979926825
1403636586863555584 0.033507701 0.100469612 -0.045933291 -0.191606835 0.034999516 0.015607242 0.980723321
1403636586913555456 0.035491433 0.099980049 -0.044110481 -0.188843891 0.033236645 0.014150766 0.981342494
1403636586963555584 0.036731031 0.099803112 -0.041578423 -0.186424360 0.030971128 0.012714324 0.981898725
1403636587013555456 0.037515581 0.099460594 -0.038622957 -0.185598686 0.028719064 0.009552988 0.982159376
1403636587063555584 0.039173201 0.098015510 -0.036719427 -0.186373651 0.026725357 0.008670216 0.982077122
1403636587113555456 0.040456004 0.096701868 -0.034139540 -0.188920513 0.025633091 0.006066658 0.981639028
1403636587163555584 0.042700533 0.095951475 -0.031856757 -0.191271916 0.025594434 0.004490723 0.981193066
1403636587213555456 0.047592752 0.094474971 -0.029470390 -0.192974851 0.024113510 0.004754948 0.980895817
1403636587263555584 0.052891865 0.094651178 -0.026443221 -0.193542451 0.024653984 0.004490825 0.980771840
1403636587313555456 0.061198890 0.093181834 -0.023538893 -0.194229364 0.025052335 0.006810009 0.980612576
1403636587363555584 0.070192248 0.092599533 -0.019210471 -0.195110500 0.026779212 0.006888812 0.980391443
1403636587413555456 0.081113189 0.091929227 -0.016304716 -0.195775285 0.027695052 0.007776058 0.980226755
1403636587463555584 0.094617687 0.090635441 -0.013415774 -0.196587473 0.028259687 0.010054405 0.980027378
1403636587513555456 0.109559648 0.089278452 -0.009934569 -0.198040634 0.028617000 0.012038594 0.979701996
1403636587563555584 0.125574440 0.088337667 -0.007669602 -0.198498264 0.029587109 0.014878661 0.979541540
1403636587613555456 0.142204508 0.087350972 -0.005473666 -0.197725296 0.031894624 0.016243031 0.979603827
1403636587663555584 0.159626231 0.084806338 -0.003939442 -0.195457309 0.034435429 0.017277334 0.979955196
1403636587713555456 0.179042906 0.081732713 -0.001317542 -0.192659393 0.037118763 0.019925751 0.980360925
1403636587763555584 0.197254375 0.079972297 0.001505192 -0.188550219 0.040891193 0.022536995 0.980953038
1403636587813555456 0.215830281 0.077583358 0.003610671 -0.185992837 0.045195170 0.024063447 0.981216133
1403636587863555584 0.235695973 0.076615416 0.004999228 -0.184647128 0.047594793 0.026302565 0.981299341
1403636587913555456 0.253428787 0.076464228 0.007454067 -0.186086223 0.051176470 0.027965913 0.980801105
1403636587963555584 0.270577222 0.076522566 0.008246254 -0.189989552 0.055848829 0.028607072 0.979778826
1403636588013555456 0.286698878 0.079504043 0.009949531 -0.194950402 0.061182596 0.028225206 0.978496015
1403636588063555584 0.301769823 0.080814868 0.011970960 -0.199908450 0.065083146 0.030181361 0.977184653
1403636588113555456 0.313887358 0.082579710 0.012766428 -0.203276441 0.066415988 0.031708714 0.976351440
1403636588163555584 0.325092584 0.084974766 0.015048333 -0.205130339 0.067414656 0.031755634 0.975893617
1403636588213555456 0.334375381 0.086257659 0.015321180 -0.205425203 0.066398621 0.031122765 0.975921631
1403636588263555584 0.341481000 0.087927312 0.015452132 -0.204419985 0.065914750 0.031848330 0.976142108
1403636588313555456 0.345857710 0.088651925 0.016104482 -0.202933639 0.064829722 0.032681379 0.976497293
1403636588363555584 0.348245144 0.090086758 0.016250037 -0.200828433 0.063159496 0.032826617 0.977036953
1403636588413555456 0.349072337 0.090679735 0.016024373 -0.199339941 0.062154248 0.034329191 0.977354527
1403636588463555584 0.347470880 0.091400377 0.015613511 -0.198676974 0.062232323 0.035127725 0.977456212
1403636588513555456 0.344526082 0.091226742 0.014758013 -0.199626833 0.063722827 0.034288496 0.977196395
1403636588563555584 0.339213967 0.090319261 0.013363972 -0.199441344 0.064670257 0.033296090 0.977206349
1403636588613555456 0.330739796 0.088971034 0.011521034 -0.199103087 0.064660586 0.033593483 0.977265775
1403636588663555584 0.320698440 0.087855190 0.009382673 -0.198623627 0.063740499 0.033304907 0.977433681
1403636588713555456 0.308494508 0.088075303 0.007034086 -0.198905259 0.062021092 0.033911072 0.977466166
1403636588763555584 0.294740289 0.088716015 0.003729220 -0.200140864 0.059716124 0.032059375 0.977419972
1403636588813555456 0.280399084 0.089237526 0.001368131 -0.202035666 0.057180520 0.031731986 0.977192402
1403636588863555584 0.263574839 0.090896793 -0.000577491 -0.202427313 0.054864608 0.031437084 0.977253675
1403636588913555456 0.245220184 0.091711074 -0.002309218 -0.202221200 0.052088298 0.031438798 0.977448165
1403636588963555584 0.226090714 0.091992877 -0.004478820 -0.201506659 0.049342822 0.030643839 0.977763414
1403636589013555456 0.206115648 0.091342881 -0.007979788 -0.199746624 0.046099111 0.029474778 0.978318691
1403636589063555584 0.184806898 0.090101287 -0.011163965 -0.197654128 0.042648289 0.028757328 0.978921354
1403636589113555456 0.161851674 0.089375407 -0.014817208 -0.194517255 0.040117294 0.026178882 0.979728699
1403636589163555584 0.139455408 0.088362150 -0.017257812 -0.192193806 0.037461247 0.024918964 0.980325103
1403636589213555456 0.116114251 0.086045489 -0.021038942 -0.190995738 0.035239492 0.024564521 0.980650544
1403636589263555584 0.092159979 0.084983334 -0.024057895 -0.191263720 0.033330414 0.023414159 0.980693161
1403636589313555456 0.068063416 0.085330226 -0.026557442 -0.192528024 0.030615551 0.020714508 0.980594993
1403636589363555584 0.044079296 0.085752964 -0.029387148 -0.194750145 0.027590139 0.020728135 0.980245650
1403636589413555456 0.019413903 0.087384902 -0.031384472 -0.196210280 0.025827937 0.017862806 0.980058908
1403636589463555584 -0.002946354 0.087719873 -0.033200704 -0.197057083 0.023580356 0.016956324 0.979961693
1403636589513555456 -0.027707051 0.088959686 -0.034702349 -0.196201608 0.022859177 0.016240064 0.980162561
1403636589563555584 -0.051538289 0.091203086 -0.036124550 -0.194649950 0.020747036 0.015271856 0.980534434
1403636589613555456 -0.076010793 0.093472525 -0.037216119 -0.193321988 0.020340217 0.013872072 0.980826378
1403636589663555584 -0.100902535 0.095160089 -0.038785156 -0.192195788 0.019275907 0.012046088 0.981093347
1403636589713555456 -0.123510003 0.097000957 -0.040401395 -0.191694096 0.017379029 0.011826592 0.981229544
1403636589763555584 -0.146301940 0.099627696 -0.042459659 -0.191850320 0.014017764 0.012052957 0.981250048
1403636589813555456 -0.167231992 0.102786012 -0.042739395 -0.194005981 0.009894995 0.010982414 0.980888963
1403636589863555584 -0.187274739 0.105193026 -0.045090415 -0.197369769 0.006111523 0.010757016 0.980251014
1403636589913555456 -0.205435574 0.108946316 -0.046841662 -0.200152636 0.001821578 0.010355481 0.979708314
1403636589963555584 -0.221593767 0.112748846 -0.047550272 -0.201642856 -0.003480129 0.010003784 0.979401827
1403636590013555456 -0.235672206 0.114796504 -0.047518291 -0.201422393 -0.008100040 0.010805329 0.979411364
1403636590063555584 -0.248239294 0.115299165 -0.047520440 -0.199408665 -0.010990490 0.010507988 0.979798436
1403636590113555456 -0.258312196 0.116551712 -0.048808251 -0.195308164 -0.014051433 0.009958610 0.980590701
1403636590163555584 -0.266015291 0.115196958 -0.050360415 -0.192584679 -0.016645724 0.009922544 0.981088996
1403636590213555456 -0.269814372 0.114124417 -0.051732108 -0.190647721 -0.017729968 0.009532720 0.981452107
1403636590263555584 -0.269174039 0.114147842 -0.052565396 -0.189530894 -0.018603344 0.008843205 0.981658697
1403636590313555456 -0.267881542 0.114100426 -0.053380817 -0.190636903 -0.016872365 0.006471033 0.981494248
1403636590363555584 -0.260518104 0.113385916 -0.055133890 -0.191357315 -0.015770458 0.007991542 0.981361210
1403636590413555456 -0.252545953 0.112499692 -0.056392193 -0.192131639 -0.012735414 0.005952056 0.981268466
1403636590463555584 -0.241707638 0.111846171 -0.057758257 -0.191709846 -0.008246461 0.005012979 0.981404185
1403636590513555456 -0.226582974 0.109809458 -0.059705824 -0.190670162 -0.005565218 0.004853545 0.981626391
1403636590563555584 -0.210190386 0.108824693 -0.060944017 -0.188740030 -0.001983935 0.004749178 0.982013583
1403636590613555456 -0.192718551 0.106356062 -0.061856199 -0.187605098 0.001112579 0.003952771 0.982235968
1403636590663555584 -0.174087510 0.104394913 -0.063625708 -0.186603904 0.004946625 0.003533887 0.982416391
1403636590713555456 -0.152377695 0.103127986 -0.064193986 -0.186869338 0.007421432 0.003942615 0.982348800
1403636590763555584 -0.131197795 0.102174357 -0.063556880 -0.188547701 0.010464954 0.004864114 0.981996238
1403636590813555456 -0.109699145 0.101654507 -0.063754521 -0.191205740 0.011586189 0.006560366 0.981459677
1403636590863555584 -0.086345173 0.101435855 -0.061731249 -0.194280595 0.012780526 0.009276905 0.980818868
1403636590913555456 -0.063178882 0.101848163 -0.061099105 -0.196325019 0.014693244 0.009963885 0.980378151
1403636590963555584 -0.038979109 0.102487944 -0.059198514 -0.197530255 0.016522497 0.009840288 0.980108142
1403636591013555456 -0.014790573 0.101058401 -0.057842180 -0.198065072 0.016527535 0.010970389 0.979988098
1403636591063555584 0.009168196 0.101200357 -0.055809394 -0.196840107 0.015078655 0.011809510 0.980248511
1403636591113555456 0.031683616 0.100625508 -0.052611195 -0.196256012 0.014501649 0.012805881 0.980361819
1403636591163555584 0.053254589 0.099578097 -0.050980847 -0.196312055 0.014697783 0.014310506 0.980326891
1403636591213555456 0.074482806 0.098690808 -0.048361402 -0.197362676 0.015042492 0.015229143 0.980096817
1403636591263555584 0.094145939 0.099289984 -0.045720242 -0.198313743 0.016241809 0.016402280 0.979866743
1403636591313555456 0.112596698 0.100150272 -0.041426059 -0.200115323 0.017766923 0.016812319 0.979466975
1403636591363555584 0.127656430 0.102544084 -0.039272938 -0.200982794 0.020474741 0.017277742 0.979228377
1403636591413555456 0.140940800 0.105026521 -0.035359040 -0.201293901 0.022902934 0.018648759 0.979085565
1403636591463555584 0.151812911 0.107371539 -0.032597251 -0.201382026 0.024103245 0.020233074 0.979007185
1403636591513555456 0.162935287 0.110382549 -0.028380482 -0.200252801 0.025976593 0.019917093 0.979197323
1403636591563555584 0.171408162 0.112774119 -0.023182139 -0.196911603 0.032978918 0.020194573 0.979658306
1403636591613555456 0.180017054 0.115050264 -0.016650975 -0.190458253 0.040907755 0.021036239 0.980616987
1403636591663555584 0.186435446 0.116685539 -0.011746831 -0.181370676 0.047633443 0.021201076 0.982031763
1403636591713555456 0.190907747 0.117321506 -0.007100254 -0.171341628 0.053341575 0.020695440 0.983548939
1403636591763555584 0.194523096 0.117319547 -0.001636453 -0.161166891 0.059136171 0.018984422 0.984970927
1403636591813555456 0.197807074 0.116210982 0.002643514 -0.150421545 0.065440021 0.018143328 0.986286879
1403636591863555584 0.200761825 0.115027919 0.006536748 -0.141318843 0.070472345 0.018318994 0.987282634
1403636591913555456 0.203876048 0.113682389 0.009894691 -0.135739014 0.075130567 0.019863551 0.987692118
1403636591963555584 0.206894413 0.111537866 0.014320128 -0.135726005 0.079478338 0.023504065 0.987273633
1403636592013555456 0.212113470 0.109387912 0.019513533 -0.139253482 0.083462782 0.026759397 0.986370325
1403636592063555584 0.217871532 0.107342437 0.026241932 -0.142634451 0.089016587 0.030809788 0.985282838
1403636592113555456 0.224841326 0.105611019 0.035811897 -0.146208808 0.094274521 0.034817111 0.984135747
1403636592163555584 0.232220888 0.102508381 0.044861652 -0.150445387 0.098694168 0.038657665 0.982919753
1403636592213555456 0.239771485 0.100200519 0.055324651 -0.154923618 0.102051429 0.041627482 0.981759310
1403636592263555584 0.246400177 0.097143918 0.066496737 -0.159727171 0.103623323 0.042973049 0.980766416
1403636592313555456 0.251189232 0.094047628 0.078305393 -0.163739175 0.103740692 0.043673992 0.980061173
1403636592363555584 0.254534066 0.089842245 0.091768816 -0.167347550 0.101743713 0.046359956 0.979537547
1403636592413555456 0.255768299 0.085355490 0.105949543 -0.169882193 0.097318791 0.047213186 0.979510069
1403636592463555584 0.253432870 0.080228828 0.120595135 -0.170052499 0.092479177 0.046158679 0.979999542
1403636592513555456 0.249048978 0.074710265 0.135827035 -0.167749166 0.085703254 0.043975882 0.981112301
1403636592563555584 0.243321061 0.068994366 0.151225790 -0.163476288 0.077696122 0.040841959 0.982634604
1403636592613555456 0.235109404 0.064520381 0.167058662 -0.158331364 0.068922050 0.036119562 0.984315157
1403636592663555584 0.224233329 0.060381711 0.181933820 -0.154465720 0.060732953 0.031122042 0.985638499
1403636592713555456 0.211255804 0.056773253 0.195191443 -0.152131334 0.051168639 0.025712142 0.986699879
1403636592763555584 0.194827735 0.053287420 0.208379641 -0.151620150 0.039689206 0.021775758 0.987401605
1403636592813555456 0.175259218 0.051795907 0.219865412 -0.151849404 0.026625520 0.017660802 0.987887084
1403636592863555584 0.153628618 0.050812177 0.227235332 -0.153817281 0.011427154 0.014946267 0.987920225
1403636592913555456 0.129158571 0.049441572 0.233098835 -0.157129616 -0.003635724 0.012745150 0.987489045
1403636592963555584 0.102168791 0.051383413 0.232852012 -0.159809217 -0.017785428 0.009249422 0.986944377
1403636593013555456 0.071005791 0.053660922 0.227350727 -0.162510112 -0.031941943 0.005416931 0.986174822
1403636593063555584 0.040880069 0.057244234 0.222097620 -0.164963156 -0.046160184 0.001882100 0.985217154
1403636593113555456 0.010109356 0.060977362 0.211506739 -0.167048752 -0.059106909 -0.003632684 0.984168649
1403636593163555584 -0.019218668 0.065129310 0.196331948 -0.167997792 -0.073319450 -0.005987264 0.983038723
1403636593213555456 -0.050929349 0.069536805 0.180766523 -0.168577909 -0.084183492 -0.005892010 0.982069194
1403636593263555584 -0.079765067 0.073982619 0.161079228 -0.169186980 -0.095671333 -0.004491248 0.980919242
1403636593313555456 -0.105077580 0.079073206 0.140286580 -0.171006158 -0.103535086 -0.003926018 0.979807079
1403636593363555584 -0.126862511 0.087006144 0.120333165 -0.173318416 -0.107967511 -0.004088087 0.978921354
1403636593413555456 -0.144047827 0.093966350 0.097818866 -0.175216883 -0.110158317 -0.006586298 0.978325486
1403636593463555584 -0.155680850 0.103525192 0.076080285 -0.176825061 -0.109797806 -0.007879092 0.978067100
1403636593513555456 -0.164151520 0.113466009 0.053458817 -0.178121701 -0.105745181 -0.008139609 0.978276193
1403636593563555584 -0.166045040 0.122190714 0.031637162 -0.180725560 -0.102308474 -0.004104316 0.978189349
1403636593613555456 -0.164466470 0.131937787 0.009520754 -0.184248850 -0.096492425 -0.000321516 0.978131592
1403636593663555584 -0.160008118 0.142002657 -0.010095321 -0.188830733 -0.089424588 0.004830974 0.977917612
1403636593713555456 -0.150624514 0.152020648 -0.029376574 -0.192862704 -0.078822941 0.009884086 0.978004754
1403636593763555584 -0.136473581 0.160673484 -0.047685392 -0.195879549 -0.066108309 0.016375281 0.978260040
1403636593813555456 -0.120434754 0.167707339 -0.065637246 -0.197259024 -0.048793234 0.023880137 0.978845119
1403636593863555584 -0.100284174 0.173118502 -0.080455594 -0.195552528 -0.030825494 0.031406667 0.979705393
1403636593913555456 -0.076556496 0.178099230 -0.093750246 -0.190934762 -0.012499168 0.039191850 0.980740368
1403636593963555584 -0.053567462 0.181734890 -0.103413343 -0.185316414 0.008943556 0.045462780 0.981585920
1403636594013555456 -0.026710682 0.183731809 -0.112177134 -0.179551408 0.029156622 0.051154464 0.981984973
1403636594063555584 0.001280612 0.183587670 -0.119488120 -0.175676361 0.049309656 0.056411728 0.981592596
1403636594113555456 0.029263543 0.184634134 -0.120884746 -0.172324032 0.068019159 0.062643059 0.980690420
1403636594163555584 0.057911709 0.181543872 -0.121345416 -0.173151448 0.084356032 0.068067357 0.978912354
1403636594213555456 0.087868512 0.181019828 -0.114978231 -0.173413008 0.098215833 0.071497738 0.977327824
1403636594263555584 0.117598236 0.178742111 -0.106951922 -0.173835695 0.110058971 0.073759481 0.975821555
1403636594313555456 0.146036193 0.174684107 -0.094171099 -0.174871594 0.120338202 0.074583411 0.974359274
1403636594363555584 0.174664348 0.170369476 -0.079594120 -0.174484432 0.128831059 0.073662005 0.973412395
1403636594413555456 0.202423677 0.164590642 -0.061040010 -0.172372565 0.135021567 0.071296774 0.973125696
1403636594463555584 0.230393484 0.158198327 -0.037186868 -0.168442920 0.139066204 0.067812137 0.973493218
1403636594513555456 0.253420919 0.151478365 -0.017145216 -0.162669897 0.140842527 0.063783795 0.974491417
1403636594563555584 0.272797227 0.143447340 0.006620541 -0.156550959 0.141340956 0.063791543 0.975420535
1403636594613555456 0.286706895 0.135996312 0.030428201 -0.151992351 0.140936762 0.063507840 0.976218164
1403636594663555584 0.295056403 0.128457904 0.054414235 -0.148018673 0.139566362 0.064731956 0.976944983
1403636594713555456 0.297886580 0.121002249 0.077344693 -0.146048814 0.135941163 0.064321026 0.977779388
1403636594763555584 0.292669445 0.115642764 0.098751113 -0.143852562 0.129733026 0.062248327 0.979081690
1403636594813555456 0.281014204 0.111930534 0.120360911 -0.141726956 0.119846284 0.058791921 0.980863810
1403636594863555584 0.262330800 0.107558891 0.138388425 -0.140180081 0.108691663 0.054047231 0.982656896
1403636594913555456 0.237437040 0.105831534 0.153869420 -0.138040006 0.094785035 0.046829924 0.984767854
1403636594963555584 0.206446171 0.103561401 0.164645880 -0.136798844 0.078585632 0.038415086 0.986729264
1403636595013555456 0.172384918 0.102525666 0.172064796 -0.135728255 0.058063049 0.032230482 0.988517940
1403636595063555584 0.132435545 0.102313340 0.174108103 -0.136535242 0.038223840 0.023965601 0.989607334
1403636595113555456 0.093532488 0.105337419 0.177395910 -0.138540134 0.017562365 0.017801728 0.990041077
1403636595163555584 0.054004557 0.109409973 0.178558037 -0.141055658 -0.000956845 0.010956757 0.989940584
1403636595213555456 0.016817316 0.112625033 0.172767773 -0.144060209 -0.019981813 0.007331323 0.989339948
1403636595263555584 -0.017877849 0.117031038 0.165146559 -0.146730125 -0.036888462 0.004106325 0.988479972
1403636595313555456 -0.046900764 0.122995347 0.158437431 -0.149087131 -0.052400801 0.000982721 0.987434149
1403636595363555584 -0.071410790 0.127251759 0.144567713 -0.151267871 -0.063911401 -0.002165257 0.986422122
1403636595413555456 -0.089437753 0.132915050 0.130269080 -0.152593434 -0.072209865 -0.003736114 0.985640407
1403636595463555584 -0.100647122 0.138401866 0.115374029 -0.154060438 -0.077315472 -0.005084399 0.985018730
1403636595513555456 -0.105601579 0.144026607 0.100238070 -0.156125426 -0.079340786 -0.005417058 0.984530628
1403636595563555584 -0.102595225 0.149963766 0.085019171 -0.158518821 -0.081885770 -0.006887020 0.983930409
1403636595613555456 -0.094267666 0.156470761 0.069071986 -0.160527453 -0.080228865 -0.007362371 0.983737767
1403636595663555584 -0.079290897 0.162413269 0.054965682 -0.163210556 -0.077220239 -0.008712201 0.983525991
1403636595713555456 -0.060512453 0.167946815 0.041337173 -0.164840594 -0.068891287 -0.008231952 0.983876884
1403636595763555584 -0.037582032 0.174469501 0.027062282 -0.165132463 -0.058316302 -0.008534692 0.984508812
1403636595813555456 -0.008504663 0.181182519 0.014953595 -0.165031031 -0.044726074 -0.006851601 0.985249937
1403636595863555584 0.019805677 0.188049421 0.001880348 -0.164466918 -0.028512182 -0.005759035 0.985953629
1403636595913555456 0.048205171 0.194517076 -0.009445738 -0.164807245 -0.012554027 -0.001988520 0.986243904
1403636595963555584 0.075055584 0.200722650 -0.020224448 -0.165729091 0.003368009 0.002112656 0.986163318
1403636596013555456 0.100872681 0.206848338 -0.034722757 -0.168237060 0.018383140 0.005612342 0.985559165
1403636596063555584 0.121159248 0.211900145 -0.049585536 -0.170625374 0.032938696 0.010545859 0.984728813
1403636596113555456 0.135383591 0.219001323 -0.064231507 -0.172313437 0.046979971 0.014873735 0.983808815
1403636596163555584 0.144154161 0.223867744 -0.078679860 -0.173607245 0.055196885 0.020239115 0.983058631
1403636596213555456 0.143484816 0.227958173 -0.093458228 -0.172730997 0.061829932 0.023627043 0.982742488
1403636596263555584 0.136682630 0.229144558 -0.112029582 -0.172576353 0.064493723 0.028141096 0.982479572
1403636596313555456 0.124503598 0.230227455 -0.128938243 -0.170565292 0.065813996 0.030708997 0.982666254
1403636596363555584 0.108400747 0.230538562 -0.148167476 -0.168412566 0.066991992 0.031810783 0.982922852
1403636596413555456 0.089396246 0.230603278 -0.168289423 -0.166118458 0.067614868 0.030509608 0.983311772
1403636596463555584 0.069997899 0.231244311 -0.188246995 -0.163291723 0.066558763 0.028256632 0.983924448
1403636596513555456 0.050258204 0.232638910 -0.206981033 -0.160087273 0.065022081 0.025286697 0.984634340
1403636596563555584 0.031699620 0.233559802 -0.224425375 -0.157718360 0.063299656 0.021941066 0.985208929
1403636596613555456 0.015763309 0.234349638 -0.238699853 -0.157819644 0.062820360 0.020475117 0.985254943
1403636596663555584 0.000507448 0.234694004 -0.249161527 -0.159633830 0.062953137 0.019150931 0.984980822
1403636596713555456 -0.010492831 0.235831529 -0.256226152 -0.160708115 0.061933715 0.018408641 0.984884858
1403636596763555584 -0.017671540 0.237086400 -0.257345498 -0.160520792 0.060811002 0.015832853 0.985030174
1403636596813555456 -0.021181770 0.235879853 -0.255618215 -0.158300519 0.060013749 0.014294705 0.985461771
1403636596863555584 -0.021047659 0.234417155 -0.247403234 -0.155267581 0.060190409 0.010884627 0.985976994
1403636596913555456 -0.018998403 0.231046259 -0.233113691 -0.153182313 0.061628360 0.007990568 0.986241996
1403636596963555584 -0.012541397 0.227320105 -0.214436039 -0.152814001 0.062288292 0.004913029 0.986277819
1403636597013555456 -0.004936784 0.222893670 -0.190763623 -0.154662579 0.063282758 0.004320493 0.985929072
1403636597063555584 0.003290518 0.216170475 -0.164618462 -0.160533786 0.063277528 0.003272061 0.984994471
1403636597113555456 0.012715797 0.209915489 -0.136067078 -0.165895984 0.060556117 0.003851943 0.984274685
1403636597163555584 0.022427948 0.200468138 -0.107210703 -0.171429202 0.055392571 0.002679406 0.983634293
1403636597213555456 0.032362938 0.190256014 -0.075727977 -0.174500823 0.048479643 0.000953144 0.983462393
1403636597263555584 0.039983772 0.178402796 -0.045024298 -0.175336689 0.042524949 -0.002181664 0.983587265
1403636597313555456 0.047944926 0.166297197 -0.013675027 -0.173554599 0.035037801 -0.005624335 0.984184682
1403636597363555584 0.054063648 0.153544247 0.017739374 -0.171194151 0.026965739 -0.009177511 0.984825492
1403636597413555456 0.058040731 0.140512809 0.048994534 -0.169866025 0.019485384 -0.014201399 0.985172153
1403636597463555584 0.060862713 0.129691556 0.078145683 -0.168022677 0.010789550 -0.018265689 0.985554874
1403636597513555456 0.061012760 0.120874144 0.103412718 -0.165664777 0.001387726 -0.023406718 0.985903323
1403636597563555584 0.057376213 0.113871537 0.124697641 -0.162710562 -0.009512533 -0.026208773 0.986279786
1403636597613555456 0.052108269 0.107632250 0.141310632 -0.158869356 -0.022113888 -0.026849112 0.986686707
1403636597663555584 0.042948529 0.105738580 0.151073098 -0.154036403 -0.034436733 -0.028579487 0.987051189
1403636597713555456 0.032479376 0.105115175 0.156848922 -0.149575114 -0.045886081 -0.029093022 0.987256467
1403636597763555584 0.019948516 0.106200963 0.155343533 -0.145569324 -0.054983955 -0.031286851 0.987323403
1403636597813555456 0.008549238 0.109146617 0.149333566 -0.141403422 -0.062683508 -0.032590363 0.987427831
1403636597863555584 -0.002514303 0.114270821 0.140432507 -0.138202116 -0.067569375 -0.036485564 0.987422585
1403636597913555456 -0.011571319 0.119797751 0.125410870 -0.136808217 -0.072663121 -0.039751146 0.987128854
1403636597963555584 -0.019327439 0.127272516 0.108221270 -0.137217090 -0.075458743 -0.044306464 0.986668348
1403636598013555456 -0.026332382 0.134654045 0.088675112 -0.139231339 -0.077125244 -0.047167521 0.986124456
1403636598063555584 -0.030847918 0.144065872 0.068848617 -0.142872170 -0.077611014 -0.048737288 0.985489070
1403636598113555456 -0.034138389 0.153409168 0.047454637 -0.149327099 -0.078440309 -0.048214752 0.984491646
1403636598163555584 -0.035444889 0.164536178 0.027680412 -0.156171441 -0.076509766 -0.049007736 0.983542025
1403636598213555456 -0.034701709 0.176319510 0.009577412 -0.165668637 -0.073689103 -0.049490020 0.982178450
1403636598263555584 -0.031457726 0.187901735 -0.005801059 -0.174713194 -0.071213149 -0.051582783 0.980685055
1403636598313555456 -0.027516674 0.198075593 -0.016199976 -0.182497457 -0.067852363 -0.052229155 0.979470730
1403636598363555584 -0.022262096 0.207422882 -0.022764303 -0.187150106 -0.063434973 -0.054263465 0.978777945
1403636598413555456 -0.017281849 0.216727987 -0.023398183 -0.188697755 -0.058668230 -0.055771541 0.978693366
1403636598463555584 -0.010425376 0.223036259 -0.019379780 -0.188977525 -0.056850381 -0.056890700 0.978682280
1403636598513555456 -0.004342331 0.228130370 -0.011118613 -0.185943052 -0.056070682 -0.057226039 0.979288757
1403636598563555584 0.001842947 0.231113613 0.001540340 -0.180534303 -0.058719862 -0.057898074 0.980105698
1403636598613555456 0.006672664 0.232313633 0.016463347 -0.173464566 -0.061512288 -0.056994718 0.981263399
1403636598663555584 0.012195703 0.231800169 0.034003019 -0.166673139 -0.066966482 -0.056828134 0.982092738
1403636598713555456 0.017766908 0.234628275 0.052029062 -0.155724853 -0.073377565 -0.055620030 0.983499825
1403636598763555584 0.022011990 0.237081915 0.071521267 -0.144830614 -0.080590852 -0.054532699 0.984660029
1403636598813555456 0.025842885 0.240749434 0.090112969 -0.133521736 -0.086159721 -0.052947320 0.985872746
1403636598863555584 0.030027669 0.245821074 0.109227493 -0.121781409 -0.090174146 -0.050683647 0.987152040
1403636598913555456 0.033702191 0.251952082 0.127211332 -0.111197665 -0.091581039 -0.048793681 0.988365889
1403636598963555584 0.037341844 0.259413332 0.144561753 -0.101706147 -0.091047823 -0.049195327 0.989416957
1403636599013555456 0.041024551 0.266659766 0.159732923 -0.093935013 -0.092440665 -0.048804928 0.990075231
1403636599063555584 0.042842835 0.272692829 0.172962517 -0.085507490 -0.094209641 -0.046608478 0.990777791
1403636599113555456 0.044423804 0.277489960 0.183573470 -0.076476023 -0.098076396 -0.044716634 0.991227925
1403636599163555584 0.045585375 0.280525714 0.192274183 -0.064245090 -0.102419280 -0.041671854 0.991789460
1403636599213555456 0.047128540 0.283002436 0.201429307 -0.047726154 -0.103671290 -0.040077630 0.992657185
1403636599263555584 0.047740664 0.284632802 0.210343391 -0.031895123 -0.103649668 -0.037611015 0.993390560
1403636599313555456 0.047772892 0.286307275 0.216848984 -0.018440928 -0.103436895 -0.034918994 0.993851781
1403636599363555584 0.048761006 0.288471133 0.224662587 -0.009113164 -0.102816753 -0.032446727 0.994129181
1403636599413555456 0.049520914 0.291847527 0.231633350 -0.002887348 -0.099984229 -0.033433411 0.994422913
1403636599463555584 0.049976215 0.295223415 0.238075465 -0.000555283 -0.096045189 -0.035258707 0.994752109
1403636599513555456 0.050316457 0.298474073 0.243490607 -0.001966059 -0.091700375 -0.034292553 0.995194018
1403636599563555584 0.051077489 0.301817387 0.248096243 -0.004618779 -0.087517157 -0.032510389 0.995621622
1403636599613555456 0.051904913 0.305181384 0.251465201 -0.008235126 -0.085288346 -0.031737048 0.995816648
1403636599663555584 0.052162398 0.309003741 0.255118668 -0.010631230 -0.082438268 -0.033152558 0.995987833
1403636599713555456 0.052878495 0.311761498 0.256140590 -0.009651213 -0.082105882 -0.031122962 0.996090770
1403636599763555584 0.054199670 0.311980337 0.256230831 -0.000125936 -0.083605178 -0.031091081 0.996013761
1403636599813555456 0.055624042 0.312114745 0.256106049 0.007847529 -0.083849445 -0.030306157 0.995986521
1403636599863555584 0.056222927 0.311778456 0.255506754 0.013972231 -0.084018208 -0.029276883 0.995936036
1403636599913555456 0.056762002 0.312198758 0.253656626 0.016143898 -0.085178025 -0.027212502 0.995863199
1403636599963555584 0.057189576 0.312277347 0.254231095 0.015401236 -0.083777949 -0.025950380 0.996027410
1403636600013555456 0.057957556 0.312505841 0.255360514 0.014762464 -0.083219208 -0.024774075 0.996113896
1403636600063555584 0.058921851 0.313706040 0.256019175 0.014912721 -0.084237210 -0.021595504 0.996100068
1403636600113555456 0.059441458 0.313077450 0.254984170 0.017636875 -0.085010365 -0.019585513 0.996031404
1403636600163555584 0.059454225 0.313480347 0.254094779 0.018324982 -0.084603406 -0.021427659 0.996015728
1403636600213555456 0.059443802 0.313707888 0.254685432 0.018638311 -0.084818147 -0.020233992 0.996016622
1403636600263555584 0.059489712 0.313889414 0.254998326 0.018703265 -0.085004739 -0.020130031 0.996001601
1403636600313555456 0.059155911 0.314016521 0.254475981 0.018649025 -0.085394092 -0.019174343 0.995988190
1403636600363555584 0.059332740 0.313926250 0.254783571 0.018879078 -0.085701384 -0.018551415 0.995969236
1403636600413555456 0.059332453 0.314033329 0.254498750 0.018919580 -0.085832946 -0.018772684 0.995952964
1403636600463555584 0.058926683 0.313959092 0.254473835 0.018688411 -0.086121164 -0.017972810 0.995947242
1403636600513555456 0.059439469 0.314051211 0.254252791 0.019123634 -0.085893042 -0.017952576 0.995959044
1403636600563555584 0.059595376 0.313802451 0.254238367 0.018923765 -0.085912645 -0.018499708 0.995951176
1403636600613555456 0.059146643 0.313976586 0.254169017 0.018909059 -0.085998707 -0.018131401 0.995950758
1403636600663555584 0.059147518 0.313713312 0.254987210 0.018947447 -0.085760653 -0.018406091 0.995965540
1403636600713555456 0.059222866 0.313813716 0.254613906 0.018911364 -0.085733019 -0.018626399 0.995964468
1403636600763555584 0.059173793 0.313603699 0.254397750 0.018824974 -0.086007565 -0.018166875 0.995950937
1403636600813555456 0.059205905 0.313685477 0.254854918 0.018910531 -0.085639417 -0.018432813 0.995976150
1403636600863555584 0.059019949 0.313823700 0.254550844 0.018813193 -0.085914202 -0.018094860 0.995960534
1403636600913555456 0.059371084 0.313423306 0.254189432 0.018815227 -0.085678630 -0.018546835 0.995972455
1403636600963555584 0.059231777 0.313730150 0.253998756 0.018826835 -0.085873328 -0.018308459 0.995959938
1403636601013555456 0.059170868 0.313537717 0.254396826 0.018880934 -0.085635141 -0.018600378 0.995974004
1403636601063555584 0.058985073 0.313705057 0.254479289 0.018813008 -0.085936353 -0.018138781 0.995957851
1403636601113555456 0.059175450 0.313568145 0.254317403 0.018868666 -0.085671708 -0.018442160 0.995974004
1403636601163555584 0.058855403 0.313834697 0.254612714 0.018744346 -0.085809357 -0.018277518 0.995967567
1403636601213555456 0.059060466 0.313665509 0.255018473 0.018923763 -0.085543282 -0.018591093 0.995981216
1403636601263555584 0.058995541 0.313802987 0.254408866 0.018777255 -0.085864954 -0.018026331 0.995966733
1403636601313555456 0.059139073 0.313843995 0.255651504 0.018891459 -0.085763656 -0.018388567 0.995966673
1403636601363555584 0.059154753 0.313650727 0.254327804 0.018755430 -0.085846908 -0.018143281 0.995966554
1403636601413555456 0.059202559 0.313647091 0.254868597 0.018746734 -0.085764669 -0.018345522 0.995970070
1403636601463555584 0.058930010 0.313588440 0.254120320 0.018655855 -0.085755132 -0.017810022 0.995982349
1403636601513555456 0.059070781 0.313680738 0.254299134 0.018723134 -0.085485831 -0.018372862 0.995994031
1403636601563555584 0.059153568 0.313638061 0.254607499 0.018858694 -0.085794501 -0.018055268 0.995970726
1403636601613555456 0.058859456 0.313678414 0.254021585 0.018710071 -0.085671313 -0.017907439 0.995986819
1403636601663555584 0.059251938 0.313693732 0.254352242 0.018704288 -0.085661598 -0.018065596 0.995984852
1403636601713555456 0.058998786 0.313707530 0.254236042 0.018840538 -0.085688107 -0.018362179 0.995974600
1403636601763555584 0.059233498 0.313611537 0.253891915 0.018762371 -0.085695349 -0.018211804 0.995978177
1403636601813555456 0.059076380 0.313627303 0.254360676 0.018744390 -0.085704759 -0.017908609 0.995983243
1403636601863555584 0.059058294 0.313525945 0.253927857 0.018734541 -0.085693456 -0.018249432 0.995978177
1403636601913555456 0.059224129 0.313667923 0.253937632 0.018729795 -0.085541315 -0.018148681 0.995993197
1403636601963555584 0.059067987 0.313658655 0.254550338 0.018725377 -0.085724883 -0.018306794 0.995974660
1403636602013555456 0.059103206 0.313692868 0.254334539 0.018771192 -0.085831188 -0.018067438 0.995968997
1403636602063555584 0.059238866 0.313547343 0.254175961 0.018727565 -0.085723266 -0.018305186 0.995974779
1403636602113555456 0.058871914 0.313644141 0.254085034 0.018789761 -0.085763775 -0.017702386 0.995981038
1403636602163555584 0.058997057 0.313674659 0.254611313 0.018679000 -0.085719876 -0.018331263 0.995975494
1403636602213555456 0.059057657 0.313670218 0.254065782 0.018836645 -0.085853584 -0.017831756 0.995970070
1403636602263555584 0.059100859 0.313628435 0.255374372 0.018788522 -0.085547589 -0.018245731 0.995989799
1403636602313555456 0.059092004 0.313720018 0.254464746 0.018861786 -0.085888565 -0.017984066 0.995963812
1403636602363555584 0.059249636 0.313699692 0.254887104 0.018800037 -0.085846968 -0.017966948 0.995968878
1403636602413555456 0.059132017 0.313706934 0.254508078 0.018867008 -0.085679218 -0.018349873 0.995975077
1403636602463555584 0.059165467 0.313736439 0.254411995 0.018784754 -0.085663691 -0.018228129 0.995980203
1403636602513555456 0.059086036 0.313718349 0.255142391 0.018834407 -0.085682489 -0.017908575 0.995983481
1403636602563555584 0.059101347 0.313760012 0.254518092 0.018836219 -0.085765421 -0.017631248 0.995981276
1403636602613555456 0.059180234 0.313787013 0.254902631 0.018864121 -0.085780926 -0.018141931 0.995970190
1403636602663555584 0.059177361 0.313646376 0.254601300 0.018766029 -0.085647754 -0.018003171 0.995986044
1403636602713555456 0.058995973 0.313659847 0.254355937 0.018675199 -0.085683972 -0.017895820 0.995986581
1403636602763555584 0.058956813 0.313705266 0.254485995 0.018811848 -0.085815229 -0.017787600 0.995974660
1403636602813555456 0.059057184 0.313681304 0.255186051 0.018841468 -0.085871153 -0.017974410 0.995965898
1403636602863555584 0.059044998 0.313705891 0.254144549 0.018784314 -0.085721791 -0.017669482 0.995985329
1403636602913555456 0.059141058 0.313782722 0.254949898 0.018888725 -0.085691713 -0.018259278 0.995975256
1403636602963555584 0.059060980 0.313717395 0.254382879 0.018762523 -0.085757926 -0.017756535 0.995981097
1403636603013555456 0.059160084 0.313809723 0.254755795 0.018815676 -0.085836396 -0.017929545 0.995970190
1403636603063555584 0.059005424 0.313788027 0.254177004 0.018753363 -0.085648067 -0.017849460 0.995989025
1403636603113555456 0.059117619 0.313880146 0.255115330 0.018891763 -0.085608386 -0.017921288 0.995988488
1403636603163555584 0.059077989 0.313744128 0.254560918 0.018766135 -0.085694291 -0.017662130 0.995988131
1403636603213555456 0.058981661 0.313686818 0.254462570 0.018797485 -0.085521214 -0.018049523 0.995995462
1403636603263555584 0.059105530 0.313810498 0.254606843 0.018854002 -0.085777558 -0.017494030 0.995982289
1403636603313555456 0.059009977 0.313706964 0.254977494 0.018819388 -0.085413948 -0.018028334 0.996004641
1403636603363555584 0.059245624 0.313655525 0.253727436 0.018828537 -0.085726142 -0.017678080 0.995983958
1403636603413555456 0.058996938 0.313643336 0.254585534 0.018783836 -0.085676119 -0.017764654 0.995987535
1403636603463555584 0.059082493 0.313663363 0.254525423 0.018806437 -0.085630931 -0.018020831 0.995986402
1403636603513555456 0.059017558 0.313585073 0.254317224 0.018843474 -0.085662492 -0.017646106 0.995989740
1403636603563555584 0.059045333 0.313810050 0.254237831 0.018844415 -0.085639752 -0.017835803 0.995988250
1403636603613555456 0.058993187 0.313880682 0.254555583 0.018870423 -0.085694417 -0.018092088 0.995978415
1403636603663555584 0.059033014 0.313690186 0.254328758 0.018842800 -0.085767932 -0.017645575 0.995980620
1403636603713555456 0.059050191 0.313686937 0.255052567 0.018771134 -0.085665382 -0.017606026 0.995991528
1403636603763555584 0.059187699 0.313708067 0.254894078 0.018848980 -0.085766248 -0.017802676 0.995977879
1403636603813555456 0.059139546 0.313757539 0.254533887 0.018865870 -0.085754417 -0.017684517 0.995980680
1403636603863555584 0.059190184 0.313862294 0.254780263 0.018977825 -0.085725546 -0.017441384 0.995985329
1403636603913555456 0.059024911 0.313838065 0.255100578 0.019083815 -0.085899495 -0.017708631 0.995963633
1403636603963555584 0.059291258 0.313762337 0.254969239 0.019021273 -0.085718930 -0.017739736 0.995979786
1403636604013555456 0.059126098 0.313850880 0.254491270 0.018926261 -0.085862905 -0.017440930 0.995974481
1403636604063555584 0.059257049 0.313828707 0.255099893 0.018918803 -0.085750170 -0.018022051 0.995974004
1403636604113555456 0.059406057 0.313772321 0.254150659 0.019039674 -0.085858762 -0.017392254 0.995973527
1403636604163555584 0.059275560 0.313778758 0.255034983 0.019059954 -0.085809439 -0.017567568 0.995974362
1403636604213555456 0.059079021 0.313698232 0.254066467 0.019028388 -0.085882552 -0.017556498 0.995968819
1403636604263555584 0.058912482 0.313853025 0.254585057 0.018848764 -0.085641399 -0.017958788 0.995985806
1403636604313555456 0.059078019 0.313880920 0.255281448 0.019110352 -0.085714735 -0.017681524 0.995979488
1403636604363555584 0.059039038 0.313723952 0.254578143 0.018866543 -0.085735522 -0.017739197 0.995981336
1403636604413555456 0.059117109 0.313780189 0.254926711 0.018917579 -0.085779004 -0.017557923 0.995979846
1403636604463555584 0.059181534 0.313867539 0.254947335 0.019059775 -0.085800849 -0.017787255 0.995971143
1403636604513555456 0.059126899 0.313903481 0.254674077 0.019054865 -0.085773394 -0.017841965 0.995972633
1403636604563555584 0.059208296 0.313731849 0.254484117 0.018879440 -0.085809134 -0.017694293 0.995975554
1403636604613555456 0.059346143 0.313579440 0.254290581 0.018853769 -0.085673742 -0.017907800 0.995983839
1403636604663555584 0.059267551 0.313750982 0.255146593 0.018895989 -0.085813701 -0.017865907 0.995971799
1403636604713555456 0.059021864 0.313763499 0.254527777 0.018846264 -0.085793354 -0.017653458 0.995978296
1403636604763555584 0.059160400 0.313707411 0.255119383 0.018903123 -0.085844509 -0.017740799 0.995971203
1403636604813555456 0.059013035 0.313719869 0.254490048 0.018808177 -0.085679524 -0.017819297 0.995985806
1403636604863555584 0.059115384 0.313808024 0.254649729 0.018916985 -0.085860886 -0.017732650 0.995969713
1403636604913555456 0.059276793 0.313869953 0.255005151 0.018949358 -0.085771978 -0.017751705 0.995976388
1403636604963555584 0.059032798 0.313750267 0.254380763 0.018868065 -0.085834444 -0.017492447 0.995977104
1403636605013555456 0.059304669 0.313821077 0.255166590 0.019039236 -0.085935026 -0.017665740 0.995962143
1403636605063555584 0.059321236 0.313584894 0.254891068 0.018897349 -0.085776754 -0.017785102 0.995976388
1403636605113555456 0.059451342 0.313761771 0.254812419 0.018775823 -0.085731573 -0.017913509 0.995980263
1403636605163555584 0.059118055 0.313801289 0.254403293 0.018980440 -0.085922524 -0.017643780 0.995964766
1403636605213555456 0.059307382 0.313721955 0.254364133 0.018828826 -0.085724160 -0.018000768 0.995978296
1403636605263555584 0.059110709 0.313887864 0.254424274 0.018973835 -0.085673191 -0.018063067 0.995978832
1403636605313555456 0.059184488 0.313738674 0.254944503 0.018915126 -0.085764334 -0.017984221 0.995973527
1403636605363555584 0.059262771 0.313714415 0.254878491 0.018852340 -0.085782312 -0.017676508 0.995978713
1403636605413555456 0.059217084 0.313706189 0.254845977 0.018887803 -0.085885204 -0.017660618 0.995969415
1403636605463555584 0.059074666 0.313759744 0.254474223 0.018900655 -0.085821331 -0.017722897 0.995973587
1403636605513555456 0.059223961 0.313651174 0.254457742 0.018884622 -0.085723832 -0.017907878 0.995978951
1403636605563555584 0.059166159 0.313679725 0.254590839 0.018881256 -0.085900463 -0.017538549 0.995970368
1403636605613555456 0.059162434 0.313687205 0.254306525 0.018939480 -0.085756846 -0.017781017 0.995977402
1403636605663555584 0.059108626 0.313768059 0.254592240 0.018900080 -0.085883781 -0.017613651 0.995970190
1403636605713555456 0.059121620 0.313810319 0.254349262 0.018934686 -0.085680224 -0.017937602 0.995981216
1403636605763555584 0.059227254 0.313698232 0.255070239 0.018823409 -0.085825041 -0.017628739 0.995976388
1403636605813555456 0.059085146 0.313694686 0.254960954 0.018769417 -0.085644200 -0.018038595 0.995985627
1403636605863555584 0.059125576 0.313725919 0.254224539 0.018927190 -0.085784033 -0.017601395 0.995978475
1403636605913555456 0.059139777 0.313822150 0.255008787 0.018915644 -0.085679688 -0.018056381 0.995979488
1403636605963555584 0.059464969 0.313630760 0.255036771 0.018910667 -0.085765928 -0.017763441 0.995977461
1403636606013555456 0.059036132 0.313677579 0.255138785 0.018713459 -0.085552618 -0.017880920 0.995997429
1403636606063555584 0.059245795 0.313694596 0.254913718 0.018676821 -0.085621826 -0.017792834 0.995993733
1403636606113555456 0.059097670 0.313759714 0.254509985 0.018792827 -0.085543208 -0.018163614 0.995991647
1403636606163555584 0.059174698 0.313829631 0.255278468 0.018796667 -0.085599542 -0.018019311 0.995989323
1403636606213555456 0.059211094 0.313820720 0.255114675 0.018923812 -0.085651845 -0.018103808 0.995980859
1403636606263555584 0.059090301 0.313661754 0.254214615 0.018660152 -0.085680395 -0.018032821 0.995984674
1403636606313555456 0.059178039 0.313860089 0.255112737 0.018886885 -0.085705124 -0.018088132 0.995977283
1403636606363555584 0.059319422 0.313731641 0.254382998 0.018799571 -0.085768841 -0.017719219 0.995980084
1403636606413555456 0.059094664 0.313650757 0.254438907 0.018790541 -0.085532658 -0.017930334 0.995996773
1403636606463555584 0.059182663 0.313838124 0.255043626 0.018869840 -0.085757606 -0.017740339 0.995979369
1403636606513555456 0.058983617 0.313785613 0.254728228 0.018812189 -0.085659005 -0.018036153 0.995983601
1403636606563555584 0.059282295 0.313723415 0.255401313 0.018781723 -0.085729338 -0.017632850 0.995985329
1403636606613555456 0.059168637 0.313619107 0.254853904 0.018781442 -0.085756570 -0.017665429 0.995982409
1403636606663555584 0.059061509 0.313662767 0.254374683 0.018775014 -0.085596204 -0.018075097 0.995989025
1403636606713555456 0.059099812 0.313586593 0.254479975 0.018751035 -0.085706063 -0.017840667 0.995984256
1403636606763555584 0.059196770 0.313822299 0.254916012 0.018842028 -0.085689813 -0.018079732 0.995979607
1403636606813555456 0.059098143 0.313712627 0.254867345 0.018937575 -0.085653678 -0.017987380 0.995982587
1403636606863555584 0.059235733 0.313654035 0.254880786 0.018725572 -0.085690208 -0.017779509 0.995987177
1403636606913555456 0.058968756 0.313722670 0.254688561 0.018789995 -0.085633770 -0.018042047 0.995986044
1403636606963555584 0.059028212 0.313691437 0.255186886 0.018831773 -0.085580423 -0.018059546 0.995989561
1403636607013555456 0.059180837 0.313693434 0.254922837 0.018757172 -0.085675925 -0.017839348 0.995986700
1403636607063555584 0.059079852 0.313699156 0.255282581 0.018831965 -0.085697226 -0.017683316 0.995986283
1403636607113555456 0.059118658 0.313776702 0.255289584 0.018799761 -0.085821949 -0.017844589 0.995973289
1403636607163555584 0.059327058 0.313815653 0.254956037 0.018917432 -0.085711181 -0.018082146 0.995976269
1403636607213555456 0.059202190 0.313766390 0.255312949 0.018848734 -0.085617714 -0.017875738 0.995989323
1403636607263555584 0.059145078 0.313688785 0.255078256 0.018812653 -0.085727684 -0.017731359 0.995983183
1403636607313555456 0.059188541 0.313712716 0.254685998 0.018767891 -0.085712940 -0.017807111 0.995983958
1403636607363555584 0.059038095 0.313755095 0.254829437 0.018842090 -0.085585535 -0.018275058 0.995984972
1403636607413555456 0.059208091 0.313804746 0.255614340 0.018888235 -0.085747786 -0.017739991 0.995979846
1403636607463555584 0.059254725 0.313725799 0.254831374 0.018911516 -0.085745260 -0.018086098 0.995973408
1403636607513555456 0.059223842 0.313506246 0.254131794 0.018754067 -0.085641071 -0.017892225 0.995988846
1403636607563555584 0.059166361 0.313716263 0.255237818 0.018906400 -0.085707232 -0.018049128 0.995977461
1403636607613555456 0.059113055 0.313770711 0.254580855 0.018780712 -0.085724011 -0.017877720 0.995981455
1403636607663555584 0.059000313 0.313563257 0.254381895 0.018781714 -0.085692160 -0.017935770 0.995983124
1403636607713555456 0.059175380 0.313769698 0.255035758 0.018752329 -0.085708171 -0.017878633 0.995983362
1403636607763555584 0.059069950 0.313715041 0.254395545 0.018869612 -0.085701063 -0.017992886 0.995979667
1403636607813555456 0.059309822 0.313638210 0.254792660 0.018793456 -0.085689276 -0.017932309 0.995983243
1403636607863555584 0.059004076 0.313539714 0.254531920 0.018728731 -0.085619614 -0.017865716 0.995991647
1403636607913555456 0.059162535 0.313692629 0.255016446 0.018834643 -0.085595392 -0.017927902 0.995990634
1403636607963555584 0.059524123 0.313612312 0.254695803 0.018738594 -0.085674442 -0.017983640 0.995984614
1403636608013555456 0.059205461 0.313694835 0.254836679 0.018800182 -0.085721210 -0.017839529 0.995982051
1403636608063555584 0.059231672 0.313680410 0.254816920 0.018747419 -0.085694231 -0.017976882 0.995982885
1403636608113555456 0.059333839 0.313603520 0.254156590 0.018729359 -0.085694082 -0.017921994 0.995984197
1403636608163555584 0.059209552 0.313756615 0.254864961 0.018801749 -0.085763901 -0.017962709 0.995976090
1403636608213555456 0.059215572 0.313690603 0.255115718 0.018794084 -0.085544556 -0.017982014 0.995994806
1403636608263555584 0.059292234 0.313730478 0.255202711 0.018777262 -0.085890032 -0.017843263 0.995967805
1403636608313555456 0.059248924 0.313754588 0.254859239 0.018874373 -0.085692935 -0.018011646 0.995979965
1403636608363555584 0.059503958 0.313655108 0.254724473 0.018836785 -0.085692495 -0.017902719 0.995982647
1403636608413555456 0.059227847 0.313584417 0.254703045 0.018802850 -0.085567273 -0.018069636 0.995991051
1403636608463555584 0.059252769 0.313816041 0.255266875 0.018845120 -0.085548066 -0.018096503 0.995991409
1403636608513555456 0.059378188 0.313649416 0.255438179 0.018768799 -0.085703656 -0.017729467 0.995986104
1403636608563555584 0.059243772 0.313647747 0.255062610 0.018763790 -0.085537814 -0.018084148 0.995994091
1403636608613555456 0.059401844 0.313645959 0.254531503 0.018783802 -0.085706092 -0.017744334 0.995985329
1403636608663555584 0.059247237 0.313646525 0.255112827 0.018751796 -0.085577115 -0.018141268 0.995989859
1403636608713555456 0.059080679 0.313634008 0.255095005 0.018768681 -0.085583717 -0.018152107 0.995988786
1403636608763555584 0.059214350 0.313696176 0.255275726 0.018760202 -0.085697711 -0.017797461 0.995985568
1403636608813555456 0.059311960 0.313689947 0.255142927 0.018804939 -0.085630834 -0.017976673 0.995987236
1403636608863555584 0.059180412 0.313634485 0.255047232 0.018811587 -0.085691184 -0.017855149 0.995984137
1403636608913555456 0.059084002 0.313593298 0.254985780 0.018768243 -0.085551970 -0.018073725 0.995992959
1403636608963555584 0.059066292 0.313851953 0.255001724 0.018851496 -0.085539773 -0.018122684 0.995991528
1403636609013555456 0.059254438 0.313614547 0.255108684 0.018749313 -0.085683964 -0.017816382 0.995986581
1403636609063555584 0.059022624 0.313586891 0.255239308 0.018685119 -0.085600324 -0.018066391 0.995990515
1403636609113555456 0.058944806 0.313550591 0.254545480 0.018726364 -0.085732274 -0.017791135 0.995983303
1403636609163555584 0.058994029 0.313694030 0.254503697 0.018731726 -0.085655712 -0.017852809 0.995988727
1403636609213555456 0.059083208 0.313744664 0.255151302 0.018809639 -0.085688241 -0.018015649 0.995981514
1403636609263555584 0.059648968 0.313723713 0.255150586 0.018788928 -0.085759386 -0.018052008 0.995975137
1403636609313555456 0.059064824 0.313725471 0.254709363 0.018732646 -0.085673407 -0.017878482 0.995986700
1403636609363555584 0.059299003 0.313694417 0.255260319 0.018759141 -0.085575432 -0.018384155 0.995985448
1403636609413555456 0.059170701 0.313785732 0.255036622 0.018844748 -0.085695773 -0.017781587 0.995984375
1403636609463555584 0.059319969 0.313679934 0.254988730 0.018776366 -0.085729159 -0.018077839 0.995977461
1403636609513555456 0.059058063 0.313785523 0.255071431 0.018868212 -0.085876450 -0.017911401 0.995966077
1403636609563555584 0.058974065 0.313772827 0.254443854 0.018843859 -0.085637704 -0.017933741 0.995986700
1403636609613555456 0.058923814 0.313763052 0.254795849 0.018732892 -0.085548595 -0.018093094 0.995993555
1403636609663555584 0.058989640 0.313828349 0.254378259 0.018860077 -0.085592031 -0.017999321 0.995989144
1403636609713555456 0.059167627 0.313692868 0.255156726 0.018828928 -0.085744046 -0.017734591 0.995981395
1403636609763555584 0.059263561 0.313599139 0.254958391 0.018904300 -0.085744470 -0.017737104 0.995979905
1403636609813555456 0.059030235 0.313799441 0.254427642 0.018768396 -0.085574001 -0.017983228 0.995992720
1403636609863555584 0.058973696 0.313776642 0.254606664 0.018805295 -0.085679471 -0.017863534 0.995985091
1403636609913555456 0.059148666 0.313733429 0.255107701 0.018795962 -0.085769489 -0.017597396 0.995982230
1403636609963555584 0.059209183 0.313653320 0.255229473 0.018841429 -0.085708193 -0.017933469 0.995980680
1403636610013555456 0.059217565 0.313610613 0.254588097 0.018775057 -0.085749313 -0.017758161 0.995981514
1403636610063555584 0.059375398 0.313747406 0.254780591 0.018755406 -0.085724019 -0.017751735 0.995984197
1403636610113555456 0.059316751 0.313670605 0.254806846 0.018825471 -0.085763626 -0.017516168 0.995983601
1403636610163555584 0.059169281 0.313843489 0.254917353 0.018954568 -0.085626766 -0.017943224 0.995985329
1403636610213555456 0.058959916 0.313749313 0.254339337 0.018803174 -0.085706092 -0.017810201 0.995983779
1403636610263555584 0.059079219 0.313789487 0.255108804 0.018701164 -0.085470580 -0.018188011 0.995999098
1403636610313555456 0.059235442 0.313651681 0.254651815 0.018803848 -0.085793063 -0.017775537 0.995976925
1403636610363555584 0.059249502 0.313663244 0.254914403 0.018753024 -0.085723318 -0.017757377 0.995984197
1403636610413555456 0.059199996 0.313665718 0.254945606 0.018805834 -0.085717291 -0.017845085 0.995982170
1403636610463555584 0.059174929 0.313732803 0.255089611 0.018913236 -0.085731864 -0.017623886 0.995982826
1403636610513555456 0.059315741 0.313797712 0.255506188 0.018838812 -0.085638776 -0.017951332 0.995986402
1403636610563555584 0.059273440 0.313728392 0.255180299 0.018859172 -0.085708186 -0.017724110 0.995984077
1403636610613555456 0.059107829 0.313749850 0.255144268 0.018773764 -0.085681506 -0.017823236 0.995986223
1403636610663555584 0.059166331 0.313740224 0.255028218 0.018836588 -0.085794821 -0.017725918 0.995977044
1403636610713555456 0.059189484 0.313768625 0.255149215 0.018787989 -0.085672736 -0.017799713 0.995987177
1403636610763555584 0.059075546 0.313659579 0.255136698 0.018611172 -0.085542485 -0.018018760 0.995997727
1403636610813555456 0.059317555 0.313650668 0.254997671 0.018694481 -0.085582308 -0.018691098 0.995980322
1403636610863555584 0.059131317 0.313589782 0.254821002 0.018584087 -0.085584238 -0.018384058 0.995987952
1403636610913555456 0.059043847 0.313511789 0.254986018 0.018545633 -0.085486397 -0.018532177 0.995994329
1403636610963555584 0.059041131 0.313679874 0.254797399 0.018517332 -0.085592218 -0.018660383 0.995983362
1403636611013555456 0.059008654 0.313768089 0.254317403 0.018765619 -0.085532241 -0.018430494 0.995988131
1403636611063555584 0.059130996 0.313735157 0.254498243 0.018682556 -0.085872509 -0.018138884 0.995965779
1403636611113555456 0.059112258 0.313753754 0.255255431 0.018671902 -0.085581511 -0.018149348 0.995990872
1403636611163555584 0.059112497 0.313632101 0.255126894 0.018705584 -0.085857697 -0.018067287 0.995967984
1403636611213555456 0.059325334 0.313630432 0.255036205 0.018584652 -0.085767023 -0.018366680 0.995972514
1403636611263555584 0.059498008 0.313675076 0.255262375 0.018710829 -0.085879199 -0.017964328 0.995967865
1403636611313555456 0.059291262 0.313650638 0.255560338 0.018732356 -0.085807428 -0.018317260 0.995967209
1403636611363555584 0.059109025 0.313527942 0.255117238 0.018363919 -0.086189516 -0.017720871 0.995951891
1403636611413555456 0.058835637 0.313740462 0.254436374 0.018729394 -0.085877836 -0.018084558 0.995965421
1403636611463555584 0.059489280 0.313885272 0.255211771 0.018426482 -0.086088002 -0.016806407 0.995975375
1403636611513555456 0.059862390 0.313871115 0.254510432 0.018784042 -0.085073426 -0.018871820 0.996018827
1403636611563555584 0.059825480 0.313767195 0.254596204 0.018529119 -0.085566357 -0.017831022 0.996000588
1403636611613555456 0.059915237 0.313981533 0.255453646 0.018811999 -0.085657127 -0.018204028 0.995980740
1403636611663555584 0.059763405 0.313712001 0.255043924 0.018559800 -0.085565053 -0.017778259 0.996001065
1403636611713555456 0.059703954 0.313832283 0.254916966 0.018975219 -0.085364401 -0.017987357 0.996006668
1403636611763555584 0.059677489 0.313987166 0.254926473 0.018819835 -0.085596494 -0.017908657 0.995991170
1403636611813555456 0.059463255 0.313765585 0.255009115 0.018700153 -0.085460335 -0.017446952 0.996013284
1403636611863555584 0.059759419 0.313846707 0.254345298 0.019094346 -0.085169241 -0.017881881 0.996022999
1403636611913555456 0.059819981 0.313811839 0.255245119 0.018877605 -0.085708678 -0.017786717 0.995982587
1403636611963555584 0.059534695 0.313869774 0.254760385 0.018829858 -0.085716009 -0.017854447 0.995981634
1403636612013555456 0.059537992 0.313798130 0.255103409 0.019141918 -0.085908361 -0.017369069 0.995967686
1403636612063555584 0.059752978 0.313824207 0.255313665 0.018664017 -0.085424520 -0.018305188 0.996001601
1403636612113555456 0.059268877 0.313762277 0.254695714 0.018564429 -0.086175337 -0.016905935 0.995963573
1403636612163555584 0.059481658 0.313650817 0.255290687 0.018945146 -0.086611785 -0.016727721 0.995921493
1403636612213555456 0.059259977 0.313760042 0.254980296 0.018528111 -0.086320169 -0.016764179 0.995954096
1403636612263555584 0.060173955 0.313987970 0.255432069 0.019261567 -0.084984019 -0.019937674 0.995996594
1403636612313555456 0.059676409 0.313900143 0.254991591 0.018917136 -0.086575329 -0.016302522 0.995932281
1403636612363555584 0.060071789 0.314185143 0.255619884 0.019021742 -0.085081361 -0.019847007 0.995994687
1403636612413555456 0.059493765 0.313718289 0.254825532 0.018931072 -0.086294733 -0.016404731 0.995954692
1403636612463555584 0.060194071 0.314173013 0.255425751 0.019191414 -0.085378692 -0.019011071 0.995982289
1403636612513555456 0.059758566 0.313691765 0.254558086 0.018917682 -0.085889257 -0.017365679 0.995973706
1403636612563555584 0.060122438 0.313783854 0.255670905 0.019134691 -0.085542277 -0.018500747 0.995979011
1403636612613555456 0.059854310 0.313969612 0.254932225 0.018923277 -0.085792594 -0.017477829 0.995979965
1403636612663555584 0.060138043 0.313941538 0.256156564 0.019092796 -0.085457452 -0.018485175 0.995987356
1403636612713555456 0.059480987 0.313693255 0.254301816 0.018831531 -0.085818015 -0.017288567 0.995982826
1403636612763555584 0.060038500 0.313700855 0.254332036 0.019008191 -0.085644916 -0.018100569 0.995979905
1403636612813555456 0.059628274 0.313762009 0.254371136 0.018942377 -0.085617885 -0.018037861 0.995984614
1403636612863555584 0.059994970 0.313870281 0.254383802 0.019001208 -0.085882008 -0.017935151 0.995962620
1403636612913555456 0.059728816 0.313836336 0.254191577 0.019065244 -0.085608520 -0.017854579 0.995986402
1403636612963555584 0.059846714 0.313823074 0.254778355 0.019144457 -0.085890554 -0.017160028 0.995972812
1403636613013555456 0.059953485 0.313801408 0.254878938 0.019179679 -0.085649468 -0.017780568 0.995981991
1403636613063555584 0.059954647 0.313929051 0.254779041 0.019261813 -0.086117782 -0.017220061 0.995949924
1403636613113555456 0.059993930 0.313928694 0.254524559 0.019031368 -0.085782051 -0.017913299 0.995971084
1403636613163555584 0.059621632 0.313972622 0.254606515 0.019279230 -0.085956879 -0.017040143 0.995966554
1403636613213555456 0.060083795 0.313852310 0.254497409 0.019146776 -0.085634843 -0.017999113 0.995979965
1403636613263555584 0.059857156 0.313976616 0.254727662 0.019057933 -0.085846990 -0.017787155 0.995967209
1403636613313555456 0.059818771 0.313875049 0.254727095 0.019306580 -0.085672207 -0.017581897 0.995981157
1403636613363555584 0.059701640 0.314019620 0.254639089 0.019214725 -0.085868768 -0.017400969 0.995969176
1403636613413555456 0.059998170 0.313864142 0.254177213 0.019146336 -0.085815057 -0.017681966 0.995970190
1403636613463555584 0.059885167 0.314081401 0.254741251 0.019299001 -0.085788667 -0.017697766 0.995969176
1403636613513555456 0.059848059 0.313904226 0.254424453 0.019188304 -0.085632585 -0.018138345 0.995976865
1403636613563555584 0.059751280 0.313938856 0.254063517 0.019213391 -0.085849620 -0.017423708 0.995970428
1403636613613555456 0.059810802 0.313920349 0.254234970 0.019306859 -0.085729487 -0.017691113 0.995974243
1403636613663555584 0.059784099 0.313910484 0.254455805 0.019140495 -0.085776351 -0.017526703 0.995976329
1403636613713555456 0.059885319 0.313915193 0.254927933 0.019290200 -0.085883059 -0.017625699 0.995962501
1403636613763555584 0.059637953 0.313919276 0.254226625 0.019333346 -0.085641965 -0.017538337 0.995984018
1403636613813555456 0.059797570 0.313927293 0.254422545 0.019287782 -0.085648842 -0.017588273 0.995983422
1403636613863555584 0.059751529 0.313912421 0.254728675 0.019251829 -0.085772492 -0.017524865 0.995974541
1403636613913555456 0.059775569 0.314033121 0.255122930 0.019293645 -0.085701138 -0.017596977 0.995978653
1403636613963555584 0.059709270 0.314058900 0.254285157 0.019190980 -0.085530818 -0.017896380 0.995989919
1403636614013555456 0.060130700 0.314179480 0.255254716 0.019427972 -0.085812286 -0.017514560 0.995967925
1403636614063555584 0.059757929 0.314047456 0.254806727 0.019296210 -0.085606255 -0.017738787 0.995984256
1403636614113555456 0.059832629 0.314052820 0.254740685 0.019380357 -0.085744239 -0.017474631 0.995975375
1403636614163555584 0.059811704 0.314025015 0.254737228 0.019316526 -0.085660838 -0.017733481 0.995979249
1403636614213555456 0.059734948 0.313960165 0.254616916 0.019235106 -0.085578948 -0.017846115 0.995985866
1403636614263555584 0.060003035 0.314031512 0.254793346 0.019112581 -0.085744433 -0.017752785 0.995975614
1403636614313555456 0.059808519 0.314018458 0.254925221 0.019329455 -0.085696451 -0.017643640 0.995977521
1403636614363555584 0.059729241 0.314102948 0.255220383 0.019297125 -0.085709050 -0.017616687 0.995977521
1403636614413555456 0.059743468 0.313872188 0.254507840 0.019213393 -0.085706010 -0.017359391 0.995983899
1403636614463555584 0.059784077 0.314013094 0.254889280 0.019174259 -0.085494563 -0.017910654 0.995993078
1403636614513555456 0.059931383 0.313897371 0.254308283 0.019206310 -0.085810170 -0.017481348 0.995972931
1403636614563555584 0.059750855 0.313829958 0.254683673 0.019196682 -0.085698813 -0.017570132 0.995981216
1403636614613555456 0.059859566 0.313895285 0.254487991 0.019259978 -0.085711308 -0.017458798 0.995980859
1403636614663555584 0.059736747 0.313915402 0.254870653 0.019170763 -0.085665807 -0.017645210 0.995983183
1403636614713555456 0.059855584 0.314018250 0.254348516 0.019304903 -0.085946769 -0.017094363 0.995966017
1403636614763555584 0.059773095 0.313919038 0.254635125 0.019219957 -0.085556090 -0.017787864 0.995989144
1403636614813555456 0.059838340 0.313956022 0.254172593 0.019270187 -0.085635871 -0.017788600 0.995981276
1403636614863555584 0.059729826 0.313934416 0.254776835 0.019208878 -0.085502446 -0.018074799 0.995988786
1403636614913555456 0.059784628 0.313950509 0.255004466 0.019238677 -0.085653193 -0.017609240 0.995983601
1403636614963555584 0.059987683 0.314043671 0.254692584 0.019314574 -0.085562028 -0.017888995 0.995984972
1403636615013555456 0.059897363 0.313869953 0.254152328 0.019323293 -0.085813038 -0.017281096 0.995973945
1403636615063555584 0.059878029 0.314004660 0.254671156 0.019250045 -0.085639454 -0.017721554 0.995982587
1403636615113555456 0.059857834 0.313971639 0.254438579 0.019264923 -0.085686021 -0.017664965 0.995979309
1403636615163555584 0.059797585 0.314031065 0.254882783 0.019148076 -0.085636988 -0.017695531 0.995985210
1403636615213555456 0.059862956 0.314034313 0.254820168 0.019342909 -0.085592441 -0.017774755 0.995983899
1403636615263555584 0.059829548 0.313921362 0.254373908 0.019233171 -0.085532457 -0.017878870 0.995989263
1403636615313555456 0.059817843 0.313934922 0.254785955 0.019150898 -0.085527129 -0.017832000 0.995992184
1403636615363555584 0.059906192 0.313991427 0.254493773 0.019119922 -0.085635073 -0.017618842 0.995987296
1403636615413555456 0.059761230 0.313932866 0.254853129 0.019125674 -0.085596457 -0.017854407 0.995986283
1403636615463555584 0.059973553 0.314008355 0.254988760 0.019218929 -0.085723586 -0.017638227 0.995977402
1403636615513555456 0.059782047 0.313900799 0.254745215 0.019128202 -0.085679501 -0.017609019 0.995983481
1403636615563555584 0.059844460 0.314073861 0.254814565 0.019223146 -0.085606262 -0.017595744 0.995988190
1403636615613555456 0.059762675 0.314034611 0.254947275 0.019300267 -0.085742824 -0.017694399 0.995973170
1403636615663555584 0.059880923 0.314005941 0.254848093 0.019269908 -0.085696205 -0.017554378 0.995980263
1403636615713555456 0.059794851 0.314019859 0.254665345 0.019242777 -0.085611053 -0.017686030 0.995985746
1403636615763555584 0.059887994 0.313833088 0.254933983 0.019206898 -0.085742883 -0.017454969 0.995979190
1403636615813555456 0.059882443 0.313960552 0.254529983 0.019217389 -0.085821204 -0.017364431 0.995973825
1403636615863555584 0.059935201 0.313895464 0.255000442 0.019172065 -0.085821256 -0.017499231 0.995972395
1403636615913555456 0.059687216 0.313843161 0.254260689 0.019143892 -0.085696496 -0.017532729 0.995983064
1403636615963555584 0.060008388 0.314119995 0.254938692 0.019224197 -0.085763656 -0.017526755 0.995975852
1403636616013555456 0.059815615 0.313997298 0.254906356 0.019261166 -0.085657693 -0.017677577 0.995981574
1403636616063555584 0.059795424 0.313999087 0.254814297 0.019170837 -0.085576504 -0.017997975 0.995984554
1403636616113555456 0.059786245 0.313956648 0.254578948 0.019165130 -0.085614502 -0.017695906 0.995986819
1403636616163555584 0.059828836 0.313990891 0.254787326 0.019230848 -0.085760683 -0.017740762 0.995972157
1403636616213555456 0.059762448 0.313955843 0.254529774 0.019267764 -0.085612983 -0.017849384 0.995982230
1403636616263555584 0.059881669 0.314024746 0.254836410 0.019208364 -0.085590281 -0.017933991 0.995983779
1403636616313555456 0.059704438 0.313970208 0.254668176 0.019077953 -0.085521042 -0.017879631 0.995993197
1403636616363555584 0.059750043 0.313986748 0.254624933 0.019292545 -0.085730746 -0.017449869 0.995978653
1403636616413555456 0.059828788 0.314109266 0.254861772 0.019299597 -0.085666090 -0.017732026 0.995979130
1403636616463555584 0.059843138 0.314064890 0.254779428 0.019253014 -0.085706957 -0.017586216 0.995979130
1403636616513555456 0.059879027 0.314046979 0.254818648 0.019347215 -0.085634187 -0.017832475 0.995979190
1403636616563555584 0.059685383 0.314012021 0.254850984 0.019349948 -0.085573755 -0.017834049 0.995984256
1403636616613555456 0.059830423 0.313928932 0.254372507 0.019219885 -0.085705176 -0.017565653 0.995980263
1403636616663555584 0.059780903 0.313893139 0.254620433 0.019170247 -0.085527688 -0.017816253 0.995992005
1403636616713555456 0.059668597 0.313982934 0.254999548 0.019236149 -0.085714363 -0.017561013 0.995979249
1403636616763555584 0.059847262 0.314025998 0.254818588 0.019243715 -0.085682973 -0.017585345 0.995981336
1403636616813555456 0.059780899 0.313976794 0.254786074 0.019171361 -0.085586600 -0.017762164 0.995987892
1403636616863555584 0.059865683 0.314022601 0.254878998 0.019259607 -0.085604526 -0.017973715 0.995980918
1403636616913555456 0.059708815 0.313940167 0.254755497 0.019154731 -0.085627362 -0.017659077 0.995986581
1403636616963555584 0.059938848 0.313954562 0.254612386 0.019190406 -0.085559539 -0.017818896 0.995988846
1403636617013555456 0.059827622 0.313936025 0.254564762 0.019175787 -0.085646376 -0.017821880 0.995981634
1403636617063555584 0.059890818 0.314242005 0.255005777 0.019260095 -0.085756458 -0.017385440 0.995978236
1403636617113555456 0.059823133 0.313921362 0.254438490 0.019151874 -0.085540369 -0.017907377 0.995989621
1403636617163555584 0.059786122 0.313958168 0.255139321 0.019180486 -0.085639544 -0.017682677 0.995984614
1403636617213555456 0.059702352 0.314038754 0.254839689 0.019272150 -0.085616857 -0.017832529 0.995982111
1403636617263555584 0.059733469 0.313983977 0.255276084 0.019115277 -0.085577592 -0.017874006 0.995987773
1403636617313555456 0.059699755 0.313942909 0.254888028 0.019199885 -0.085583031 -0.017851647 0.995986044
1403636617363555584 0.059662424 0.313928366 0.255121410 0.019254265 -0.085586309 -0.017883088 0.995984197
1403636617413555456 0.059825793 0.314018637 0.254978746 0.019297773 -0.085758291 -0.017340027 0.995978177
1403636617463555584 0.059851136 0.313992798 0.254513204 0.019193675 -0.085572183 -0.017808232 0.995987892
1403636617513555456 0.059772350 0.313945085 0.254906863 0.019157402 -0.085772291 -0.017562669 0.995975733
1403636617563555584 0.059807237 0.314033329 0.254609019 0.019232946 -0.085614406 -0.017684584 0.995985687
1403636617613555456 0.059780188 0.313957006 0.254894167 0.019152639 -0.085570253 -0.017833220 0.995988429
1403636617663555584 0.059753265 0.314056396 0.255049050 0.019168274 -0.085672170 -0.017608346 0.995983362
1403636617713555456 0.059643764 0.313864797 0.254698366 0.019217584 -0.085605405 -0.017821327 0.995984375
1403636617763555584 0.059671365 0.314041406 0.255011022 0.019277383 -0.085662745 -0.017627480 0.995981693
1403636617813555456 0.059930645 0.313939393 0.254573047 0.019140139 -0.085715361 -0.017615205 0.995980024
1403636617863555584 0.059853613 0.313908756 0.254407942 0.019152505 -0.085648820 -0.017757647 0.995983005
1403636617913555456 0.059872668 0.314041585 0.254788756 0.019167539 -0.085607387 -0.017801542 0.995985508
1403636617963555584 0.059872855 0.313952684 0.255190194 0.019144086 -0.085718505 -0.017696096 0.995978236
1403636618013555456 0.059933145 0.314119875 0.254745692 0.019252548 -0.085681029 -0.017651256 0.995980203
1403636618063555584 0.059726126 0.314111650 0.255027831 0.019327164 -0.085669450 -0.017701801 0.995978832
1403636618113555456 0.059784226 0.314092249 0.254706055 0.019259179 -0.085558333 -0.017915169 0.995985925
1403636618163555584 0.059672792 0.314026505 0.255021632 0.019239267 -0.085654207 -0.017714184 0.995981634
1403636618213555456 0.059661731 0.313908756 0.254770428 0.019152068 -0.085453153 -0.017942997 0.995996475
1403636618263555584 0.059934758 0.314227343 0.255108267 0.019299101 -0.085624874 -0.017906297 0.995979548
1403636618313555456 0.059692707 0.313950986 0.254600555 0.019228699 -0.085533425 -0.017936045 0.995988250
1403636618363555584 0.059730466 0.314075857 0.254644424 0.019272273 -0.085584372 -0.017846830 0.995984614
1403636618413555456 0.059779461 0.313935071 0.254804105 0.019311108 -0.085599929 -0.017854730 0.995982409
1403636618463555584 0.059926834 0.313998371 0.254777312 0.019250022 -0.085604817 -0.017928712 0.995981872
1403636618513555456 0.059705064 0.313906521 0.254416347 0.019264264 -0.085953511 -0.017722514 0.995955229
1403636618563555584 0.059739064 0.314111441 0.254999489 0.019405492 -0.085969351 -0.017531333 0.995954454
1403636618613555456 0.059674144 0.313928664 0.254557341 0.019259557 -0.085734881 -0.017716672 0.995974302
1403636618663555584 0.059845623 0.314063728 0.254646093 0.019393215 -0.085764997 -0.017472005 0.995973408
1403636618713555456 0.059618190 0.313935786 0.254847348 0.019185483 -0.085290737 -0.017795134 0.996012449
1403636618763555584 0.059923608 0.314084202 0.255053908 0.019441981 -0.085609600 -0.017635463 0.995982945
1403636618813555456 0.059601225 0.313891023 0.254405141 0.019333838 -0.085542902 -0.017519698 0.995992839
1403636618863555584 0.059721712 0.313923955 0.254796386 0.019332966 -0.085747279 -0.017123716 0.995982170
1403636618913555456 0.059733566 0.314037800 0.254572779 0.019332815 -0.086225353 -0.017299550 0.995937824
1403636618963555584 0.059720974 0.313923657 0.254284263 0.019359292 -0.085910924 -0.017777294 0.995956063
1403636619013555456 0.059976932 0.314046234 0.254408866 0.019362664 -0.086131044 -0.017388625 0.995943844
1403636619063555584 0.059791584 0.313835174 0.253888518 0.019101705 -0.086028881 -0.017134285 0.995962143
1403636619113555456 0.059704803 0.313903332 0.254164994 0.019254971 -0.085835233 -0.017079312 0.995976806
1403636619163555584 0.059834648 0.313996524 0.254486799 0.019276600 -0.085609704 -0.017543536 0.995987773
1403636619213555456 0.059750751 0.313925087 0.254385322 0.019278513 -0.085504167 -0.017571026 0.995996296
1403636619263555584 0.059645966 0.313886374 0.254570812 0.019366518 -0.085446611 -0.017671036 0.995997787
1403636619313555456 0.059811298 0.313954949 0.254907370 0.019187711 -0.085584559 -0.017375436 0.995994568
1403636619363555584 0.059869517 0.313952923 0.254803061 0.019280894 -0.086010136 -0.017418027 0.995955408
1403636619413555456 0.059810031 0.314073861 0.255013853 0.019355478 -0.085862257 -0.017883867 0.995958447
1403636619463555584 0.059558008 0.313991010 0.254563481 0.019386906 -0.085752048 -0.017538566 0.995973468
1403636619513555456 0.059732188 0.313988149 0.254419029 0.019210104 -0.085775919 -0.017620290 0.995973408
1403636619563555584 0.059897549 0.313991308 0.254336715 0.019318631 -0.085626498 -0.017667754 0.995983303
1403636619613555456 0.059889495 0.313993126 0.254602015 0.019260222 -0.085657470 -0.017863885 0.995978296
1403636619663555584 0.059885170 0.313891917 0.254471123 0.019253712 -0.085672922 -0.017935602 0.995975792
1403636619713555456 0.059798595 0.314012647 0.254794061 0.019262757 -0.085596122 -0.017653553 0.995987296
1403636619763555584 0.059900679 0.314005494 0.254812300 0.019297153 -0.085589848 -0.017736772 0.995985627
1403636619813555456 0.059947498 0.314059079 0.254944116 0.019242587 -0.085572749 -0.017627468 0.995990098
1403636619863555584 0.059703149 0.313922435 0.254632562 0.019277412 -0.085608922 -0.017588248 0.995987058
1403636619913555456 0.059995215 0.314002663 0.254625052 0.019315684 -0.085590884 -0.017679449 0.995986223
1403636619963555584 0.059701618 0.313940167 0.254574180 0.019305354 -0.085594095 -0.017863240 0.995982885
1403636620013555456 0.059795327 0.314130127 0.254869521 0.019250907 -0.085693851 -0.017628958 0.995979548
1403636620063555584 0.059706338 0.313878596 0.254585892 0.019218285 -0.085482575 -0.017877245 0.995993853
1403636620113555456 0.059689220 0.314101040 0.255024016 0.019247480 -0.085591771 -0.017890137 0.995983720
1403636620163555584 0.059712429 0.313934863 0.254875362 0.019151611 -0.085516036 -0.017766474 0.995994270
1403636620213555456 0.059777070 0.314003736 0.254577845 0.019282399 -0.085442841 -0.018289298 0.995988548
1403636620263555584 0.059733674 0.313929915 0.254990548 0.019212868 -0.085477918 -0.018096594 0.995990396
1403636620313555456 0.059886206 0.313956618 0.254699677 0.019100124 -0.085424632 -0.018119387 0.995996714
1403636620363555584 0.059823122 0.313937157 0.255268931 0.019163020 -0.085401185 -0.018162861 0.995996773
1403636620413555456 0.059792262 0.314094335 0.254891306 0.019250853 -0.085503399 -0.017955935 0.995990038
1403636620463555584 0.059797965 0.314033270 0.255319834 0.019245697 -0.085520178 -0.017881541 0.995990038
1403636620513555456 0.059942745 0.314142615 0.255516946 0.019358626 -0.085639201 -0.017714819 0.995980620
1403636620563555584 0.059654038 0.314069599 0.254938513 0.019408876 -0.085396551 -0.017868435 0.995997727
1403636620613555456 0.059706036 0.314044803 0.254786551 0.019312022 -0.085592479 -0.017706348 0.995985687
1403636620663555584 0.059736449 0.314071476 0.255313069 0.019362407 -0.085593686 -0.017652618 0.995985568
1403636620713555456 0.060027231 0.314009130 0.254705250 0.019323358 -0.085599840 -0.017778508 0.995983541
1403636620763555584 0.059735712 0.314007282 0.254876345 0.019301955 -0.085622564 -0.017783368 0.995981932
1403636620813555456 0.059860222 0.314109504 0.254968017 0.019275242 -0.085547380 -0.017849712 0.995987713
1403636620863555584 0.059890769 0.314049244 0.254845977 0.019240484 -0.085625291 -0.017876210 0.995981216
1403636620913555456 0.059934594 0.314169407 0.254980922 0.019385338 -0.085540175 -0.017960493 0.995984197
1403636620963555584 0.059853569 0.314045250 0.255170584 0.019339191 -0.085592449 -0.017693922 0.995985389
1403636621013555456 0.059963673 0.314065069 0.254767329 0.019315820 -0.085488118 -0.018153498 0.995986521
1403636621063555584 0.059998993 0.314130813 0.254865259 0.019451825 -0.085513271 -0.017774509 0.995988548
1403636621113555456 0.059741315 0.313951105 0.254458219 0.019381605 -0.085638650 -0.017547837 0.995983183
1403636621163555584 0.060113572 0.314065844 0.255726248 0.019354904 -0.085704304 -0.017662449 0.995976031
1403636621213555456 0.059659325 0.314004779 0.254590183 0.019291803 -0.085668586 -0.017272362 0.995987177
1403636621263555584 0.060085300 0.313888103 0.254839927 0.019247241 -0.085568801 -0.017937347 0.995984852
1403636621313555456 0.059887759 0.313952923 0.254714280 0.019294707 -0.085488163 -0.017763222 0.995993972
1403636621363555584 0.060060553 0.314020723 0.254721582 0.019250525 -0.085662022 -0.017728677 0.995980501
1403636621413555456 0.059930805 0.314027786 0.255332232 0.019275317 -0.085580945 -0.017621679 0.995988905
1403636621463555584 0.060279921 0.314053565 0.255029917 0.019238953 -0.085621513 -0.017771725 0.995983422
1403636621513555456 0.059676971 0.314016640 0.254968733 0.019242557 -0.085603528 -0.017732928 0.995985627
1403636621563555584 0.060138606 0.313934475 0.254665047 0.019245705 -0.085475631 -0.018111449 0.995989680
1403636621613555456 0.060098492 0.313936144 0.254612297 0.019362014 -0.085796572 -0.017370887 0.995973051
1403636621663555584 0.059995111 0.313923180 0.255202949 0.019337883 -0.085709944 -0.017338824 0.995981514
1403636621713555456 0.059994251 0.313992500 0.255099297 0.019321987 -0.085634641 -0.017656695 0.995982707
1403636621763555584 0.059672270 0.314021975 0.255014002 0.019205345 -0.085647382 -0.017486537 0.995986938
1403636621813555456 0.060032107 0.314102799 0.255421847 0.019370187 -0.085631646 -0.017859155 0.995978475
1403636621863555584 0.059666380 0.314007103 0.255123645 0.019174039 -0.085564069 -0.017757922 0.995989859
1403636621913555456 0.060016453 0.313998878 0.255266815 0.019296465 -0.085686937 -0.017613092 0.995979488
1403636621963555584 0.059826333 0.314126432 0.255753428 0.019350788 -0.085586637 -0.017948667 0.995981097
1403636622013555456 0.059904050 0.314084798 0.255643338 0.019420534 -0.085652851 -0.017676659 0.995978892
1403636622063555584 0.059969112 0.314105272 0.255100667 0.019292388 -0.085703768 -0.017725671 0.995976150
1403636622113555456 0.059915774 0.313986331 0.255122900 0.019254198 -0.085649863 -0.017886134 0.995978653
1403636622163555584 0.059978172 0.313973904 0.255216569 0.019249452 -0.085645258 -0.017774977 0.995981157
1403636622213555456 0.059897579 0.314027727 0.255245328 0.019398080 -0.085583620 -0.017976332 0.995979905
1403636622263555584 0.059980471 0.314044893 0.255211860 0.019387342 -0.085535236 -0.017987216 0.995984137
1403636622313555456 0.059989434 0.314154893 0.255115688 0.019349800 -0.085627593 -0.017749665 0.995981157
1403636622363555584 0.059870053 0.313994884 0.254993618 0.019320652 -0.085629463 -0.017753251 0.995981514
1403636622413555456 0.059914459 0.314064652 0.254885614 0.019333070 -0.085636839 -0.017764498 0.995980382
1403636622463555584 0.059715331 0.314000934 0.255067915 0.019231608 -0.085570596 -0.017801790 0.995987415
1403636622513555456 0.060024790 0.314108133 0.255334407 0.019401561 -0.085704967 -0.017606461 0.995976031
1403636622563555584 0.060067497 0.313934594 0.254670769 0.019272294 -0.085503578 -0.017691236 0.995994329
1403636622613555456 0.059994727 0.314052016 0.254671991 0.019248163 -0.085545100 -0.017822294 0.995988905
1403636622663555584 0.060123932 0.314079285 0.255510718 0.019409996 -0.085758775 -0.017719286 0.995969236
1403636622713555456 0.059807613 0.314076483 0.255302906 0.019298377 -0.085510686 -0.017679932 0.995993435
1403636622763555584 0.059876028 0.314225197 0.255311728 0.019364130 -0.085411623 -0.018005092 0.995994806
1403636622813555456 0.059947450 0.314121276 0.255728871 0.019496562 -0.085693486 -0.017496388 0.995977104
1403636622863555584 0.060172312 0.314234585 0.255356312 0.019573918 -0.085478269 -0.017627694 0.995991766
1403636622913555456 0.059768960 0.313976496 0.254612029 0.019395979 -0.085350320 -0.017685929 0.996005177
1403636622963555584 0.059858549 0.313922346 0.255452394 0.019484410 -0.085385337 -0.017485624 0.996004045
1403636623013555456 0.059792407 0.313826621 0.254990339 0.019471617 -0.085161693 -0.018007720 0.996014059
1403636623063555584 0.059696529 0.313857675 0.255029082 0.019435758 -0.085017554 -0.018373383 0.996020436
1403636623113555456 0.059673823 0.313764304 0.254912019 0.019472191 -0.085002482 -0.017861655 0.996030331
1403636623163555584 0.059731074 0.313835919 0.255231410 0.019584430 -0.085072994 -0.017635191 0.996026099
1403636623213555456 0.059832457 0.313789278 0.255067647 0.019348897 -0.085053660 -0.017985618 0.996026099
1403636623263555584 0.059760939 0.313803703 0.255399823 0.019392947 -0.085096829 -0.017883657 0.996023417
1403636623313555456 0.059847150 0.313668102 0.254818410 0.019518228 -0.084784463 -0.018376151 0.996038616
1403636623363555584 0.059995655 0.313593417 0.255112618 0.019646594 -0.085323997 -0.017367989 0.996008098
1403636623413555456 0.059907109 0.313705564 0.254579455 0.019640336 -0.085010722 -0.018195907 0.996020257
1403636623463555584 0.060091551 0.313611507 0.255121410 0.019639358 -0.085160054 -0.017594343 0.996018350
1403636623513555456 0.060079254 0.313634247 0.255201340 0.019530538 -0.085253328 -0.017485995 0.996014416
1403636623563555584 0.059988450 0.313523054 0.255206317 0.019441245 -0.085149460 -0.017459987 0.996025503
1403636623613555456 0.060105469 0.313523948 0.255384982 0.019404102 -0.084592514 -0.018055759 0.996062994
1403636623663555584 0.059824213 0.313545614 0.255420029 0.019275934 -0.084929727 -0.017534392 0.996046126
1403636623713555456 0.059744526 0.313185036 0.254408598 0.019334882 -0.084433928 -0.018059554 0.996077776
1403636623763555584 0.059928350 0.313294053 0.254142284 0.019195562 -0.084488794 -0.017324507 0.996088862
1403636623813555456 0.059774019 0.313484401 0.253979862 0.018990373 -0.084195755 -0.017309504 0.996117890
1403636623863555584 0.059906196 0.313238800 0.254088432 0.019125374 -0.084288985 -0.017070115 0.996111572
1403636623913555456 0.060157809 0.313666195 0.255271226 0.019047797 -0.084195122 -0.017213386 0.996118486
1403636623963555584 0.060057342 0.313524246 0.254863083 0.018875912 -0.083757631 -0.017463418 0.996154308
1403636624013555456 0.060251400 0.313601732 0.254588991 0.018933542 -0.083729751 -0.017759478 0.996150315
1403636624063555584 0.060108252 0.313522577 0.254951745 0.018953435 -0.083600819 -0.017574573 0.996164083
1403636624113555456 0.060160581 0.313460916 0.254739255 0.018695218 -0.083083235 -0.017375693 0.996215701
1403636624163555584 0.060274161 0.313439339 0.255307615 0.018446516 -0.082964107 -0.017038379 0.996236145
1403636624213555456 0.060439367 0.313517421 0.255441546 0.018434832 -0.082996234 -0.016503936 0.996242642
1403636624263555584 0.060621604 0.313450813 0.254997313 0.017811446 -0.083166540 -0.016414830 0.996241271
1403636624313555456 0.061004415 0.313482434 0.254729539 0.015139396 -0.081749283 -0.017605074 0.996382415
1403636624363555584 0.062244676 0.314205378 0.254073173 0.010406379 -0.079738244 -0.019032836 0.996579826
1403636624413555456 0.064041510 0.314482212 0.253027022 0.006475253 -0.078143165 -0.019619294 0.996728063
1403636624463555584 0.066749096 0.315151185 0.251160502 0.002106706 -0.076884881 -0.018216236 0.996871352
1403636624513555456 0.069845885 0.315748453 0.247934118 -0.002661737 -0.075035438 -0.018902067 0.996998191
1403636624563555584 0.073755421 0.316300482 0.246615455 -0.006141218 -0.072983131 -0.019211378 0.997129202
1403636624613555456 0.077814497 0.316940665 0.244484141 -0.006634634 -0.071383834 -0.021193912 0.997201681
1403636624663555584 0.083197430 0.317446768 0.242343321 -0.004529811 -0.070771962 -0.022704732 0.997223794
1403636624713555456 0.088885270 0.319706351 0.239030957 -0.004083734 -0.068729721 -0.027274910 0.997254074
1403636624763555584 0.095513314 0.320848912 0.234147578 -0.001355181 -0.067790613 -0.030133825 0.997243464
1403636624813555456 0.103177398 0.323531926 0.230979577 -0.004181132 -0.065759361 -0.037322775 0.997128487
1403636624863555584 0.111191452 0.323766798 0.224493399 -0.007972207 -0.063644618 -0.044091783 0.996966243
1403636624913555456 0.120064691 0.323256552 0.216427803 -0.014460741 -0.061672296 -0.051845223 0.996644080
1403636624963555584 0.127901152 0.320740134 0.208736241 -0.020271312 -0.059138291 -0.059768770 0.996252716
1403636625013555456 0.134991288 0.315633744 0.199709386 -0.026330074 -0.057742905 -0.065001041 0.995865107
1403636625063555584 0.140723675 0.308610082 0.190271601 -0.032354396 -0.056950163 -0.068593413 0.995492220
1403636625113555456 0.144956931 0.299192309 0.180050313 -0.037611872 -0.056957193 -0.069536641 0.995241582
1403636625163555584 0.147356182 0.287934721 0.172095418 -0.040165268 -0.058355443 -0.064886339 0.995374918
1403636625213555456 0.148964494 0.274296343 0.163511008 -0.038999900 -0.060126167 -0.061454196 0.995533645
1403636625263555584 0.149832934 0.260252893 0.156460255 -0.035340626 -0.061693743 -0.058339369 0.995761752
1403636625313555456 0.150516808 0.249085069 0.151068613 -0.031725120 -0.063556567 -0.055219892 0.995944202
1403636625363555584 0.150276542 0.242892116 0.148441702 -0.029544055 -0.064489946 -0.054344859 0.995999396
1403636625413555456 0.150834233 0.241565868 0.147080660 -0.031236337 -0.065412484 -0.054001153 0.995906293
1403636625463555584 0.150884151 0.244121790 0.147679642 -0.034403987 -0.065507732 -0.054705497 0.995757222
1403636625513555456 0.150967091 0.248455212 0.150603592 -0.035755880 -0.066173956 -0.054176889 0.995694399
1403636625563555584 0.150607690 0.252114862 0.153490722 -0.036621250 -0.066674665 -0.054909118 0.995589435
1403636625613555456 0.149519324 0.252863497 0.156750038 -0.036641337 -0.066910617 -0.056162998 0.995502949
1403636625663555584 0.147612378 0.249683738 0.160195112 -0.035118103 -0.067178525 -0.056671653 0.995510936
1403636625713555456 0.144950151 0.241458476 0.163384229 -0.031971604 -0.068398409 -0.055764202 0.995585144
1403636625763555584 0.141865581 0.228613913 0.166525975 -0.026849063 -0.069034904 -0.055868648 0.995686710
1403636625813555456 0.136922210 0.211034760 0.169385836 -0.022077378 -0.069484092 -0.055863414 0.995772958
1403636625863555584 0.133223921 0.190688610 0.169478759 -0.015671534 -0.071208842 -0.052818205 0.995938778
1403636625913555456 0.127930343 0.167294413 0.170955002 -0.011985588 -0.071913227 -0.051980942 0.995983362
1403636625963555584 0.122518107 0.142460257 0.170255333 -0.009034304 -0.072394162 -0.051413398 0.996009111
1403636626013555456 0.117014229 0.115807578 0.169214711 -0.006572010 -0.072979063 -0.050275218 0.996043801
1403636626063555584 0.112415783 0.090501525 0.169294566 -0.005755114 -0.074520990 -0.046854723 0.996101499
1403636626113555456 0.106569774 0.065369032 0.167788744 -0.005420087 -0.076442301 -0.041340414 0.996201873
1403636626163555584 0.103437439 0.044115029 0.169945240 -0.004566864 -0.078533255 -0.036525283 0.996231675
1403636626213555456 0.100761801 0.023838133 0.171001285 -0.003973333 -0.080288649 -0.032311291 0.996239901
1403636626263555584 0.097693473 0.004144891 0.167971969 -0.004257291 -0.081157938 -0.029796652 0.996246636
1403636626313555456 0.095245898 -0.009390171 0.169700354 -0.003879335 -0.081672728 -0.028722642 0.996237695
1403636626363555584 0.096480936 -0.018946247 0.172454476 -0.003624138 -0.081920676 -0.029307170 0.996201277
1403636626413555456 0.096438169 -0.026991643 0.172880396 -0.003195351 -0.081213214 -0.030786831 0.996216059
1403636626463555584 0.098210961 -0.031913180 0.176357269 -0.002098840 -0.080651842 -0.033893369 0.996163726
1403636626513555456 0.104135424 -0.033820186 0.185001895 0.001843118 -0.080630906 -0.036502596 0.996073663
1403636626563555584 0.106199257 -0.037375648 0.185011074 0.005619921 -0.079682723 -0.040826213 0.995968044
1403636626613555456 0.109782442 -0.038901184 0.186987564 0.009352549 -0.079277679 -0.044163827 0.995829880
1403636626663555584 0.114302047 -0.039674494 0.188224524 0.012218509 -0.079231806 -0.047058780 0.995669901
1403636626713555456 0.119475968 -0.036890592 0.189348966 0.012180706 -0.079638720 -0.048628390 0.995562434
1403636626763555584 0.125588566 -0.034085110 0.189845636 0.009880138 -0.080867916 -0.049267031 0.995457411
1403636626813555456 0.129421800 -0.031108730 0.189227492 0.006809076 -0.081320085 -0.050138149 0.995402873
1403636626863555584 0.134772852 -0.026861973 0.186458051 0.002956294 -0.081796870 -0.050784055 0.995349944
1403636626913555456 0.139833182 -0.020639988 0.186286330 -0.001148871 -0.081882283 -0.051713824 0.995298743
1403636626963555584 0.144976869 -0.013616582 0.183492362 -0.005911585 -0.081654772 -0.052845947 0.995241106
1403636627013555456 0.150906354 -0.006411743 0.181501374 -0.010458486 -0.081560142 -0.053409457 0.995181382
1403636627063555584 0.156801164 -0.000288228 0.179266497 -0.014575297 -0.081217140 -0.054215897 0.995114028
1403636627113555456 0.161833599 0.006028833 0.177380875 -0.019217337 -0.081408106 -0.054426465 0.995008111
1403636627163555584 0.166627735 0.007397952 0.175043941 -0.018059146 -0.081482992 -0.054194365 0.995036364
1403636627213555456 0.170804068 0.005905806 0.169549555 -0.015590424 -0.081489794 -0.054732326 0.995048106
1403636627263555584 0.175803900 0.002318120 0.166819111 -0.011577470 -0.081962757 -0.054329839 0.995086074
1403636627313555456 0.179463461 -0.004665500 0.161002427 -0.008179094 -0.082594991 -0.053336967 0.995121241
1403636627363555584 0.183378771 -0.012051748 0.156084761 -0.006820504 -0.082980365 -0.052169312 0.995161295
1403636627413555456 0.187436193 -0.022273529 0.149139538 -0.006527909 -0.083358712 -0.051180184 0.995183051
1403636627463555584 0.191106856 -0.035848938 0.141091734 -0.005915752 -0.083350919 -0.049983583 0.995248318
1403636627513555456 0.195727512 -0.046573773 0.134737760 -0.006771508 -0.081595197 -0.047982793 0.995486856
1403636627563555584 0.200892434 -0.055094078 0.128661275 -0.007526309 -0.078353494 -0.045612685 0.995853186
1403636627613555456 0.206796259 -0.060018238 0.123620197 -0.008926025 -0.074308641 -0.044172425 0.996216536
1403636627663555584 0.213299453 -0.059984863 0.119945198 -0.011992270 -0.070767246 -0.043434735 0.996474564
1403636627713555456 0.219395295 -0.057156760 0.117234260 -0.016820675 -0.065803207 -0.042725615 0.996775568
1403636627763555584 0.225713417 -0.050916322 0.116028003 -0.022795998 -0.059940346 -0.042115759 0.997052491
1403636627813555456 0.232972383 -0.045083385 0.115528166 -0.028406525 -0.053709410 -0.041162562 0.997303367
1403636627863555584 0.239498019 -0.038417570 0.115574419 -0.033489417 -0.046274327 -0.040517520 0.997544706
1403636627913555456 0.248016343 -0.032234833 0.116371974 -0.038109105 -0.041036818 -0.039523713 0.997648001
1403636627963555584 0.254749119 -0.029692788 0.119211614 -0.040786963 -0.035878610 -0.039320912 0.997748971
1403636628013555456 0.261209548 -0.031056955 0.120559864 -0.041981798 -0.031519316 -0.039008390 0.997858882
1403636628063555584 0.266883671 -0.035020530 0.124124631 -0.039876170 -0.027992629 -0.038481493 0.998070836
1403636628113555456 0.271755457 -0.041702520 0.129315704 -0.033104990 -0.025702840 -0.036682155 0.998447716
1403636628163555584 0.277178109 -0.052511059 0.130811989 -0.024020461 -0.024112178 -0.034461703 0.998826265
1403636628213555456 0.281942874 -0.062734365 0.136224732 -0.015582951 -0.023333590 -0.031639397 0.999105453
1403636628263555584 0.286702305 -0.077853635 0.137539759 -0.009708132 -0.022996265 -0.027331043 0.999314725
1403636628313555456 0.290759236 -0.091136061 0.143017262 -0.005438720 -0.023659609 -0.022750350 0.999446392
1403636628363555584 0.296573967 -0.105440475 0.146086738 -0.003801581 -0.024118003 -0.019994294 0.999501944
1403636628413555456 0.301376849 -0.119007945 0.146510005 -0.003537956 -0.024610123 -0.017566385 0.999536514
1403636628463555584 0.308050454 -0.130561888 0.149022758 -0.003275331 -0.024992160 -0.016033575 0.999553680
1403636628513555456 0.313556731 -0.140982330 0.152295887 -0.003894512 -0.025542337 -0.015003560 0.999553561
1403636628563555584 0.321473032 -0.150485992 0.153235629 -0.004997429 -0.026422344 -0.013655138 0.999545097
1403636628613555456 0.329787076 -0.155835181 0.155932471 -0.005213144 -0.027645551 -0.013062961 0.999518812
1403636628663555584 0.339686602 -0.161748350 0.160283253 -0.005309004 -0.028263727 -0.013222361 0.999498963
1403636628713555456 0.350921661 -0.165780902 0.163116246 -0.005487278 -0.027142627 -0.014794691 0.999507010
1403636628763555584 0.363799304 -0.167936325 0.165591925 -0.007808179 -0.023885708 -0.017523162 0.999530613
1403636628813555456 0.375615478 -0.167212322 0.172142193 -0.011099380 -0.019260662 -0.019615566 0.999560416
1403636628863555584 0.389120221 -0.167268738 0.175966069 -0.015273470 -0.014592319 -0.021586526 0.999543786
1403636628913555456 0.401800781 -0.168925688 0.178276673 -0.019593542 -0.009734596 -0.022528430 0.999506772
1403636628963555584 0.416768521 -0.171699032 0.182690278 -0.023237709 -0.006421677 -0.023411471 0.999435186
1403636629013555456 0.431095243 -0.175216123 0.188604325 -0.025929267 -0.003564972 -0.022830892 0.999396682
1403636629063555584 0.443841636 -0.183257878 0.191464946 -0.027567364 -0.000659374 -0.022242954 0.999372244
1403636629113555456 0.458513349 -0.193541750 0.192294180 -0.028209722 0.002422398 -0.022966873 0.999335229
1403636629163555584 0.471949577 -0.201073840 0.198873863 -0.028053857 0.006828437 -0.021193165 0.999358416
1403636629213555456 0.486120641 -0.210709453 0.206318900 -0.027089514 0.012359028 -0.019661598 0.999363184
1403636629263555584 0.500332892 -0.217265859 0.209782749 -0.025123401 0.017317928 -0.017445482 0.999382079
1403636629313555456 0.516071200 -0.224308535 0.219915330 -0.022909902 0.021114821 -0.014177255 0.999413967
1403636629363555584 0.528017998 -0.229453444 0.232353657 -0.020313302 0.024672879 -0.011248108 0.999425888
1403636629413555456 0.543986142 -0.234425619 0.241503432 -0.017241703 0.026844723 -0.006627845 0.999468923
1403636629463555584 0.557152569 -0.236120269 0.251512796 -0.013274951 0.031224800 -0.001122967 0.999423623
1403636629513555456 0.572593808 -0.239597142 0.263084114 -0.011400489 0.036284041 0.004194676 0.999267697
1403636629563555584 0.588152349 -0.238214597 0.273614228 -0.011713567 0.042692125 0.008446617 0.998983860
1403636629613555456 0.604899824 -0.236439109 0.285168767 -0.014717236 0.051322021 0.010401761 0.998519540
1403636629663555584 0.624059319 -0.230372608 0.298708886 -0.019659016 0.060463630 0.012600047 0.997897267
1403636629713555456 0.643938959 -0.224379450 0.311242253 -0.024272332 0.070454173 0.014899492 0.997108340
1403636629763555584 0.667417586 -0.219461024 0.321582168 -0.029164808 0.081134669 0.016574154 0.996138453
1403636629813555456 0.689496994 -0.209514230 0.339677602 -0.031417590 0.092045046 0.019642195 0.995065212
1403636629863555584 0.710259795 -0.202772006 0.354813576 -0.034393910 0.103483215 0.022443032 0.993782997
1403636629913555456 0.730880082 -0.195983410 0.375141472 -0.036066607 0.114009358 0.025266431 0.992503226
1403636629963555584 0.755012929 -0.189907193 0.390311748 -0.036448095 0.123149216 0.027690068 0.991331935
1403636630013555456 0.776709676 -0.189990342 0.405756831 -0.036760237 0.130544275 0.029942853 0.990308166
1403636630063555584 0.799395561 -0.184940964 0.431107253 -0.034064695 0.136546433 0.031604867 0.989543259
1403636630113555456 0.817073107 -0.191467673 0.449634671 -0.029863846 0.142685130 0.031392228 0.988819301
1403636630163555584 0.842508316 -0.197747484 0.463262796 -0.022887960 0.146863595 0.032395057 0.988361120
1403636630213555456 0.868475676 -0.201210648 0.487177491 -0.015377623 0.150741413 0.032788057 0.987909615
1403636630263555584 0.889228225 -0.212626502 0.501914322 -0.009765256 0.153472766 0.033514895 0.987536073
1403636630313555456 0.913168490 -0.221668869 0.520056605 -0.005826565 0.156059533 0.032671582 0.987189949
1403636630363555584 0.937965155 -0.234406963 0.528316259 -0.006703773 0.156877831 0.032630488 0.987056077
1403636630413555456 0.953280032 -0.242177442 0.559525013 -0.007532487 0.158258274 0.032781772 0.986824632
1403636630463555584 0.986656189 -0.259090304 0.571865082 -0.010841719 0.157976627 0.031636812 0.986876369
1403636630513555456 0.999518216 -0.262123227 0.592139423 -0.011709071 0.158327267 0.031149672 0.986825764
1403636630563555584 1.016956687 -0.283969373 0.602785647 -0.014030665 0.158782810 0.027938070 0.986818433
1403636630613555456 1.040901899 -0.298533499 0.602420688 -0.014881149 0.157812521 0.024792779 0.987045646
1403636630663555584 1.061788082 -0.314416796 0.628666103 -0.016301408 0.156910464 0.023273384 0.987203956
1403636630713555456 1.088607788 -0.327231407 0.640386224 -0.017196819 0.155679941 0.021183956 0.987430632
1403636630763555584 1.099407434 -0.347966760 0.657624364 -0.017889295 0.154508412 0.021123443 0.987603605
1403636630813555456 1.116876841 -0.349999785 0.681251168 -0.017636094 0.152729690 0.022851972 0.987846315
1403636630863555584 1.146417618 -0.362833709 0.693156481 -0.017596651 0.150484949 0.024702637 0.988146961
1403636630913555456 1.157309532 -0.366177201 0.725452065 -0.016736722 0.149203271 0.026382778 0.988312781
1403636630963555584 1.174589276 -0.383417249 0.749072611 -0.017311158 0.147756740 0.026996877 0.988503635
1403636631013555456 1.196506262 -0.389181435 0.770224631 -0.016926739 0.146734059 0.027425738 0.988650858
1403636631063555584 1.214205861 -0.395791441 0.776685119 -0.016107511 0.145973846 0.027340272 0.988779426
1403636631113555456 1.226915359 -0.406211078 0.804213166 -0.014717910 0.146048978 0.027062980 0.988797605
1403636631163555584 1.250211000 -0.406229496 0.819923282 -0.012961542 0.145295918 0.026893089 0.988937736
1403636631213555456 1.267588139 -0.408695012 0.841500878 -0.010745741 0.144912541 0.026913928 0.989019990
1403636631263555584 1.287116051 -0.416604936 0.866788507 -0.009618812 0.144678578 0.026025845 0.989089608
1403636631313555456 1.301847219 -0.423394829 0.891084433 -0.009769730 0.144421428 0.026113598 0.989123404
1403636631363555584 1.324804544 -0.420831352 0.914455771 -0.009423301 0.144159734 0.025557918 0.989179432
1403636631413555456 1.345106721 -0.423465490 0.932936907 -0.009607198 0.143554345 0.025392940 0.989269972
1403636631463555584 1.364605427 -0.416232169 0.954276979 -0.009133782 0.143243939 0.024841366 0.989333451
1403636631513555456 1.386619210 -0.415782511 0.975295782 -0.009561414 0.142815411 0.023959156 0.989413142
1403636631563555584 1.398118496 -0.417006344 1.010293484 -0.009630550 0.143331081 0.022542883 0.989371181
1403636631613555456 1.420693398 -0.414469033 1.018608332 -0.010401926 0.142703205 0.020365246 0.989501357
1403636631663555584 1.439909697 -0.415777594 1.040266514 -0.011262242 0.142100945 0.019421838 0.989597559
1403636631713555456 1.457375765 -0.420465678 1.061700463 -0.011724858 0.141764313 0.018860880 0.989651263
1403636631763555584 1.472942591 -0.420664161 1.085084438 -0.012164086 0.141515270 0.018257422 0.989692986
1403636631813555456 1.487847090 -0.422925740 1.103251815 -0.012038489 0.140804395 0.017558549 0.989808500
1403636631863555584 1.502333283 -0.424354196 1.127440572 -0.012551744 0.141268507 0.016461965 0.989754856
1403636631913555456 1.512329340 -0.432381481 1.155102253 -0.013606628 0.141616106 0.015727341 0.989703178
1403636631963555584 1.536473274 -0.430831283 1.159604788 -0.013274648 0.140998736 0.015605827 0.989797771
1403636632013555456 1.546271801 -0.445284098 1.180101395 -0.013774606 0.141446009 0.015236709 0.989732862
1403636632063555584 1.561866045 -0.451214850 1.204336405 -0.012113342 0.141682416 0.014814392 0.989727199
1403636632113555456 1.574556828 -0.456830055 1.221454144 -0.010452623 0.142217949 0.013428945 0.989689052
1403636632163555584 1.586565971 -0.463469326 1.243560314 -0.009065972 0.144041374 0.010472552 0.989474714
1403636632213555456 1.600085497 -0.472662032 1.263453960 -0.009608433 0.144723743 0.009417764 0.989380598
1403636632263555584 1.614089608 -0.477458686 1.273395538 -0.008884547 0.144581288 0.010470863 0.989397585
1403636632313555456 1.623763800 -0.483741969 1.295979857 -0.008786047 0.144964620 0.011564446 0.989330232
1403636632363555584 1.634031534 -0.488121748 1.314196587 -0.008454820 0.145149812 0.012397064 0.989295900
1403636632413555456 1.645025015 -0.491207689 1.335241914 -0.009432732 0.145476520 0.012934036 0.989232183
1403636632463555584 1.655103922 -0.485849679 1.355512738 -0.011739104 0.144726336 0.016650034 0.989261925
1403636632513555456 1.663281441 -0.485265076 1.372535825 -0.014980928 0.141998038 0.020152243 0.989548385
1403636632563555584 1.667798281 -0.483070314 1.397151232 -0.020037178 0.137946501 0.025474578 0.989909232
1403636632613555456 1.680732250 -0.477594048 1.413522959 -0.024420006 0.131944165 0.029852277 0.990506530
1403636632663555584 1.686378479 -0.477491051 1.435278416 -0.028051831 0.125276223 0.031933099 0.991210997
1403636632713555456 1.692856073 -0.473873019 1.458912969 -0.030361677 0.116960816 0.032190509 0.992150247
1403636632763555584 1.696937323 -0.476939768 1.492948651 -0.031894039 0.107984930 0.030522276 0.993171871
1403636632813555456 1.710942864 -0.471005082 1.504613876 -0.030794578 0.097460166 0.026284974 0.994415581
1403636632863555584 1.718015790 -0.476901770 1.530493975 -0.028283386 0.087568581 0.017308272 0.995606482
1403636632913555456 1.732731462 -0.476858705 1.552219033 -0.023543948 0.077010095 0.008633471 0.996714890
1403636632963555584 1.744790912 -0.476947516 1.571650267 -0.020404028 0.068141907 0.001180026 0.997466266
1403636633013555456 1.758799553 -0.486871570 1.589783430 -0.018213697 0.060273174 -0.006195956 0.997996509
1403636633063555584 1.766999006 -0.499553829 1.612518907 -0.018027076 0.053349983 -0.011723239 0.998344362
1403636633113555456 1.770089865 -0.506634891 1.644956350 -0.016919903 0.047564704 -0.015383159 0.998606384
1403636633163555584 1.778444409 -0.518227041 1.670286655 -0.017376935 0.042333931 -0.018789921 0.998775661
1403636633213555456 1.788290143 -0.525681615 1.695084333 -0.017171765 0.037870515 -0.020748368 0.998919666
1403636633263555584 1.802429795 -0.529774368 1.716314316 -0.018314295 0.033699282 -0.020543996 0.999053001
1403636633313555456 1.815655231 -0.534584939 1.739998102 -0.019765643 0.030285493 -0.019847309 0.999148726
1403636633363555584 1.824166298 -0.537467718 1.765880704 -0.021556817 0.027671766 -0.017821662 0.999225676
1403636633413555456 1.831230879 -0.538180172 1.794675708 -0.023626802 0.026203947 -0.015530672 0.999256670
1403636633463555584 1.833912849 -0.542063236 1.823930025 -0.025985468 0.025508232 -0.013321272 0.999248028
1403636633513555456 1.850362897 -0.540235162 1.851028681 -0.027102066 0.024683418 -0.012073317 0.999254942
1403636633563555584 1.857807636 -0.542237520 1.881486535 -0.029216789 0.025246544 -0.010636378 0.999197602
1403636633613555456 1.870902777 -0.540127993 1.909065485 -0.030984640 0.025489980 -0.009397240 0.999150574
1403636633663555584 1.872199774 -0.545757949 1.947830081 -0.032888301 0.027890807 -0.009930469 0.999020398
1403636633713555456 1.885263443 -0.545350611 1.972731471 -0.032196306 0.029064085 -0.008747849 0.999020576
1403636633763555584 1.897116780 -0.554454803 2.005026817 -0.031811468 0.030083684 -0.008394994 0.999005735
1403636633813555456 1.904953480 -0.559044242 2.041419744 -0.031303070 0.031729884 -0.006711989 0.998983562
1403636633863555584 1.915379047 -0.570521057 2.072101355 -0.030248530 0.032638799 -0.004960527 0.998997033
1403636633913555456 1.927665591 -0.583217144 2.100929976 -0.029283587 0.032680523 -0.000721404 0.999036431
1403636633963555584 1.936624527 -0.595902741 2.131006002 -0.027397545 0.032979690 0.003777622 0.999073267
1403636634013555456 1.951548696 -0.606395960 2.162852526 -0.025511967 0.032852188 0.007511839 0.999106288
1403636634063555584 1.962549686 -0.614653707 2.194555521 -0.025131235 0.033632018 0.009918361 0.999069035
1403636634113555456 1.976822734 -0.625263274 2.226401091 -0.025622746 0.033407018 0.009974740 0.999063492
1403636634163555584 1.992359400 -0.636328220 2.261910915 -0.026556293 0.033512082 0.008693210 0.999047577
1403636634213555456 2.006943941 -0.649817765 2.293002129 -0.028270263 0.033882156 0.005906033 0.999008477
1403636634263555584 2.021184206 -0.662198603 2.329465866 -0.027772980 0.034520660 0.001584585 0.999016762
1403636634313555456 2.037115574 -0.679603279 2.358396053 -0.024814256 0.034939423 -0.002280281 0.999078691
1403636634363555584 2.052075863 -0.696381867 2.396382809 -0.020086886 0.035103384 -0.005479184 0.999166787
1403636634413555456 2.074151754 -0.713249803 2.427434206 -0.015692776 0.034838241 -0.008812130 0.999230921
1403636634463555584 2.091700792 -0.730858207 2.465153217 -0.013146791 0.034504045 -0.011484931 0.999252081
1403636634513555456 2.106013298 -0.739785552 2.500336885 -0.009104330 0.034093849 -0.012601204 0.999297738
1403636634563555584 2.126393318 -0.748452246 2.534872293 -0.006416836 0.033238504 -0.013316134 0.999338150
1403636634613555456 2.137487650 -0.759979784 2.573153734 -0.005678989 0.032082696 -0.016040679 0.999340355
1403636634663555584 2.154658794 -0.766614735 2.607129097 -0.004775181 0.028794164 -0.018221481 0.999407887
1403636634713555456 2.169822693 -0.777241468 2.640524626 -0.004754251 0.025516100 -0.021367768 0.999434710
1403636634763555584 2.189354181 -0.784418106 2.671513081 -0.006408353 0.021573795 -0.023049111 0.999480963
1403636634813555456 2.200829268 -0.796230555 2.707767963 -0.008995173 0.018281914 -0.024671353 0.999487936
1403636634863555584 2.210938454 -0.806051135 2.742589235 -0.011022523 0.015152178 -0.025175050 0.999507427
1403636634913555456 2.221830130 -0.817501724 2.774211168 -0.012555971 0.011814116 -0.026216606 0.999507606
1403636634963555584 2.236782789 -0.833239257 2.802257061 -0.015164450 0.008825979 -0.027908597 0.999456465
1403636635013555456 2.250227213 -0.845383525 2.833904743 -0.015451477 0.006027530 -0.029643832 0.999422908
1403636635063555584 2.262175798 -0.858324289 2.864338398 -0.016983639 0.003906861 -0.030908715 0.999370277
1403636635113555456 2.270905972 -0.871925056 2.896600008 -0.018495804 0.002533127 -0.032224923 0.999306262
1403636635163555584 2.284465551 -0.880972028 2.928790331 -0.019164421 0.000570637 -0.031618200 0.999316096
1403636635213555456 2.295375824 -0.890972614 2.958715439 -0.020504294 -0.001000204 -0.032014295 0.999276578
1403636635263555584 2.301847935 -0.904521585 2.995740414 -0.022070527 -0.002546049 -0.031045517 0.999271035
1403636635313555456 2.310491562 -0.910244942 3.026351929 -0.023351520 -0.004097599 -0.028650768 0.999308288
1403636635363555584 2.323539734 -0.919331431 3.060806751 -0.025221929 -0.006478403 -0.025190271 0.999343455
1403636635413555456 2.329375029 -0.928924859 3.096036911 -0.026499424 -0.007213564 -0.024269009 0.999328136
1403636635463555584 2.339815378 -0.937898397 3.131286383 -0.025841337 -0.007861080 -0.022421284 0.999383688
1403636635513555456 2.351856947 -0.950199902 3.164887428 -0.026490981 -0.009068691 -0.019779081 0.999412179
1403636635563555584 2.361975908 -0.969143450 3.197140694 -0.027131364 -0.009108956 -0.019544234 0.999399245
1403636635613555456 2.372377872 -0.984381139 3.233984232 -0.026170034 -0.009334486 -0.017882969 0.999453962
1403636635663555584 2.385108948 -0.999494612 3.267026663 -0.025115186 -0.009293044 -0.016668616 0.999502361
1403636635713555456 2.397468567 -1.020207286 3.298340321 -0.023910318 -0.009026206 -0.016004901 0.999545217
1403636635763555584 2.406729221 -1.044216633 3.335367918 -0.020843085 -0.009022636 -0.014214384 0.999641001
1403636635813555456 2.420046806 -1.066434503 3.368104219 -0.016430505 -0.010014794 -0.009904904 0.999765813
1403636635863555584 2.433387041 -1.091599941 3.400879622 -0.013864333 -0.010464092 -0.006432879 0.999828458
1403636635913555456 2.448989391 -1.115298748 3.433293819 -0.014813997 -0.011489057 -0.001790574 0.999822617
1403636635963555584 2.462630987 -1.142611623 3.464369059 -0.018607479 -0.011008167 -0.001277587 0.999765456
1403636636013555456 2.477059841 -1.165244579 3.497858286 -0.023389494 -0.009651099 -0.003467949 0.999673843
1403636636063555584 2.492512703 -1.191130877 3.532603025 -0.027732339 -0.007571091 -0.007812929 0.999556184
1403636636113555456 2.512863159 -1.216095805 3.560527802 -0.030582998 -0.005892284 -0.012775479 0.999433219
1403636636163555584 2.533596039 -1.240350962 3.601130724 -0.028819727 -0.004620967 -0.016802868 0.999432683
1403636636213555456 2.551481724 -1.265591264 3.630568266 -0.023555184 -0.003186623 -0.020889305 0.999499202
1403636636263555584 2.567248583 -1.299512625 3.667207718 -0.017762478 -0.001589853 -0.024780245 0.999533832
1403636636313555456 2.585933208 -1.327483535 3.704128027 -0.011710598 -0.001168656 -0.026629096 0.999576092
1403636636363555584 2.604253292 -1.357163429 3.744573593 -0.004655744 -0.000309372 -0.028486388 0.999583244
1403636636413555456 2.621634245 -1.390213013 3.774735451 0.003535950 -0.000481218 -0.029139163 0.999568999
1403636636463555584 2.640449047 -1.418848634 3.801990032 0.010313259 -0.000600198 -0.029976280 0.999497235
1403636636513555456 2.658151627 -1.442845225 3.836693048 0.013560468 0.000549169 -0.032582778 0.999376893
1403636636563555584 2.676177740 -1.472723126 3.858694792 0.013805515 0.001550479 -0.036792189 0.999226332
1403636636613555456 2.692586660 -1.488109708 3.895719051 0.015079714 0.002983063 -0.040656727 0.999054909
1403636636663555584 2.708891153 -1.503451109 3.924951792 0.014903426 0.004521944 -0.044776909 0.998875618
1403636636713555456 2.722268105 -1.523086786 3.957448006 0.014453501 0.006064771 -0.049116384 0.998670042
1403636636763555584 2.737665892 -1.532960892 3.981744289 0.014465797 0.007174043 -0.052409142 0.998495102
1403636636813555456 2.750044584 -1.547728539 4.011745453 0.013305658 0.008822449 -0.058329273 0.998169720
1403636636863555584 2.763155937 -1.555717468 4.033897877 0.011668692 0.009719807 -0.062923856 0.997902751
1403636636913555456 2.772489786 -1.559030414 4.063192368 0.009147021 0.008359117 -0.060002558 0.998121321
1403636636963555584 2.777367592 -1.566311717 4.088511467 0.006955057 0.005778302 -0.054763194 0.998458385
1403636637013555456 2.786280870 -1.568805695 4.111313820 0.004590669 0.002433632 -0.047524605 0.998856544
1403636637063555584 2.789695263 -1.569006681 4.136435509 0.003060383 -0.000368301 -0.040874079 0.999159575
1403636637113555456 2.793484926 -1.571772456 4.158598423 0.000144224 -0.002557236 -0.036278736 0.999338388
1403636637163555584 2.800255775 -1.572939396 4.179509640 -0.003731418 -0.004493145 -0.033660173 0.999416232
1403636637213555456 2.800750017 -1.572150946 4.205591202 -0.007962665 -0.004997432 -0.033124313 0.999407053
1403636637263555584 2.806054592 -1.568495989 4.232002735 -0.010686328 -0.006042384 -0.032034881 0.999411345
1403636637313555456 2.809913158 -1.574599028 4.246424675 -0.013904554 -0.006512936 -0.032058962 0.999368012
1403636637363555584 2.812187433 -1.576825738 4.267880440 -0.015648292 -0.006500919 -0.032853402 0.999316514
1403636637413555456 2.809839487 -1.577924848 4.297155857 -0.016176695 -0.007156535 -0.031917907 0.999333978
1403636637463555584 2.814845800 -1.587292671 4.312209129 -0.018193681 -0.007992454 -0.033125035 0.999253631
1403636637513555456 2.814157963 -1.596544981 4.335932255 -0.018794062 -0.008473773 -0.032912735 0.999245584
1403636637563555584 2.820308447 -1.607439399 4.348365784 -0.020308536 -0.009610318 -0.031771291 0.999242604
1403636637613555456 2.816284657 -1.619614124 4.374057770 -0.020556299 -0.010261109 -0.031251028 0.999247491
1403636637663555584 2.819581985 -1.635326028 4.392575264 -0.021655416 -0.011025947 -0.030802032 0.999230027
1403636637713555456 2.817403316 -1.649311781 4.417432785 -0.020635976 -0.011243802 -0.031352237 0.999232054
1403636637763555584 2.819595575 -1.670527697 4.433925152 -0.019724336 -0.011866393 -0.031788077 0.999229550
1403636637813555456 2.819415569 -1.690940738 4.454179764 -0.017482923 -0.012057411 -0.032410160 0.999248981
1403636637863555584 2.821866989 -1.713001013 4.468017101 -0.015881436 -0.012683725 -0.032764006 0.999256432
1403636637913555456 2.818682671 -1.732421637 4.494745255 -0.013490697 -0.012841467 -0.032531917 0.999297142
1403636637963555584 2.821372986 -1.754113913 4.509706497 -0.011244294 -0.013327776 -0.032215320 0.999328792
1403636638013555456 2.820170879 -1.769347787 4.533165455 -0.009258303 -0.013441580 -0.032424524 0.999340892
1403636638063555584 2.817944527 -1.779215336 4.556212902 -0.007260316 -0.013775185 -0.032483302 0.999350965
1403636638113555456 2.819055557 -1.790665627 4.573455811 -0.005514669 -0.014127870 -0.032165550 0.999367476
1403636638163555584 2.822435856 -1.795152426 4.595907688 -0.003798540 -0.014815012 -0.031856295 0.999375403
1403636638213555456 2.821288586 -1.797397971 4.617748260 -0.003412914 -0.014910349 -0.032097682 0.999367654
1403636638263555584 2.824282646 -1.802702904 4.639741898 -0.003106048 -0.015257954 -0.032530881 0.999349415
1403636638313555456 2.822497845 -1.804054856 4.663482189 -0.005198515 -0.015926346 -0.030521795 0.999393702
1403636638363555584 2.822878361 -1.799675465 4.689699173 -0.010562222 -0.017544016 -0.026210360 0.999446690
1403636638413555456 2.824692488 -1.798805833 4.709263802 -0.021112060 -0.019266725 -0.021269957 0.999365151
1403636638463555584 2.825474739 -1.797607422 4.735243797 -0.031914778 -0.020991027 -0.017589789 0.999115288
1403636638513555456 2.827323675 -1.791207194 4.758483410 -0.040153001 -0.022265822 -0.012336623 0.998869300
1403636638563555584 2.831311941 -1.787925959 4.786793232 -0.044934180 -0.022823459 -0.011435193 0.998663723
1403636638613555456 2.835159063 -1.792545557 4.808932781 -0.047451824 -0.022273727 -0.013850137 0.998529077
1403636638663555584 2.840960264 -1.791644812 4.839153290 -0.045117214 -0.020947261 -0.018595332 0.998588920
1403636638713555456 2.847457409 -1.800888062 4.865687847 -0.042380448 -0.019727817 -0.022768781 0.998647213
1403636638763555584 2.854098558 -1.808138847 4.895727634 -0.037266027 -0.019387290 -0.025295112 0.998797059
1403636638813555456 2.856428385 -1.820055485 4.923844337 -0.031889766 -0.018741872 -0.026387205 0.998967230
1403636638863555584 2.862562180 -1.833076119 4.956705093 -0.027255675 -0.018835720 -0.026525550 0.999098957
1403636638913555456 2.869621992 -1.853284240 4.982335091 -0.024214340 -0.020069817 -0.024677480 0.999200642
1403636638963555584 2.875518560 -1.869952679 5.012301922 -0.021675888 -0.021328378 -0.022030467 0.999294698
1403636639013555456 2.881381989 -1.887424707 5.046076775 -0.021131357 -0.023183258 -0.016817022 0.999366403
1403636639063555584 2.888290405 -1.906734347 5.075591564 -0.020419745 -0.025223657 -0.010952865 0.999413252
1403636639113555456 2.894129515 -1.923429132 5.107079506 -0.020461462 -0.026632467 -0.006541773 0.999414444
1403636639163555584 2.902220726 -1.934439421 5.140191078 -0.020805182 -0.027736526 -0.002152088 0.999396384
1403636639213555456 2.914956808 -1.946731329 5.169811726 -0.021426370 -0.029222805 0.001075496 0.999342680
1403636639263555584 2.927111626 -1.950751424 5.205165386 -0.022136223 -0.029636974 0.002655651 0.999312043
1403636639313555456 2.943127394 -1.956695914 5.240183353 -0.022814220 -0.028145615 -0.002699513 0.999339819
1403636639363555584 2.959404230 -1.959268928 5.277981758 -0.023034252 -0.026352255 -0.008694370 0.999349475
1403636639413555456 2.975227833 -1.958355784 5.320445538 -0.023119343 -0.024281655 -0.015388789 0.999319315
1403636639463555584 2.990654469 -1.955013275 5.355019569 -0.022729220 -0.021992100 -0.021499913 0.999268472
1403636639513555456 3.007708073 -1.952394366 5.398105621 -0.021226261 -0.019753745 -0.028011058 0.999186993
1403636639563555584 3.025893211 -1.949730635 5.435304165 -0.018871237 -0.017426865 -0.034867469 0.999061763
1403636639613555456 3.047170639 -1.950464129 5.476907730 -0.017247161 -0.016274087 -0.040742502 0.998888254
1403636639663555584 3.063000441 -1.946331978 5.514350891 -0.013543763 -0.015898997 -0.042224377 0.998889804
1403636639713555456 3.076313496 -1.949145794 5.557153225 -0.009676814 -0.016614478 -0.041332234 0.998960435
1403636639763555584 3.094535828 -1.954719305 5.590095520 -0.006347043 -0.018186780 -0.038595811 0.999069214
1403636639813555456 3.107211828 -1.956745744 5.625740051 -0.004083998 -0.018823652 -0.036408696 0.999151349
1403636639863555584 3.121653795 -1.961658955 5.661098957 -0.002929937 -0.019689586 -0.033890389 0.999227285
1403636639913555456 3.134045124 -1.965735555 5.700988770 -0.002133984 -0.021033632 -0.031529177 0.999279201
1403636639963555584 3.145993233 -1.973105669 5.734181404 -0.001715751 -0.021185616 -0.030780103 0.999300182
1403636640013555456 3.158779860 -1.980741739 5.764939308 -0.001114595 -0.021955222 -0.030972660 0.999278426
1403636640063555584 3.170628071 -1.989394188 5.794611931 -0.000565526 -0.023713106 -0.032661870 0.999184966
1403636640113555456 3.182017565 -2.004590988 5.830588818 -0.000519428 -0.027023114 -0.036704894 0.998960614
1403636640163555584 3.192736149 -2.010833740 5.858761311 0.000213681 -0.030771565 -0.038142875 0.998798370
1403636640213555456 3.209950924 -2.030913353 5.882417202 -0.000395001 -0.035660941 -0.040024567 0.998562038
1403636640263555584 3.224423409 -2.044023752 5.905113697 -0.001406825 -0.039549094 -0.042274229 0.998321950
1403636640313555456 3.232494116 -2.058476686 5.932961941 -0.001967481 -0.042343054 -0.043130782 0.998169780
1403636640363555584 3.245690346 -2.067251444 5.955427647 -0.001669885 -0.045477532 -0.044288903 0.997981727
1403636640413555456 3.255713463 -2.079444647 5.986093044 -0.001691187 -0.047784720 -0.045637000 0.997813106
1403636640463555584 3.269264698 -2.089253187 6.009069920 -0.001625138 -0.049764570 -0.047466852 0.997631073
1403636640513555456 3.286510229 -2.094377518 6.032374382 -0.002368243 -0.051912118 -0.047030360 0.997540832
1403636640563555584 3.291359901 -2.105009556 6.057396889 -0.002983121 -0.053084914 -0.048610602 0.997401655
1403636640613555456 3.300403833 -2.106637955 6.081959724 -0.002482675 -0.054149073 -0.048183236 0.997366548
1403636640663555584 3.312189579 -2.114664078 6.104503632 -0.002529758 -0.054971673 -0.049231362 0.997270286
1403636640713555456 3.322355270 -2.113158941 6.128970146 -0.002889273 -0.055629782 -0.049131524 0.997237742
1403636640763555584 3.330318451 -2.115740299 6.155347347 -0.004603766 -0.056412019 -0.049519442 0.997168124
1403636640813555456 3.345571518 -2.117539644 6.175033092 -0.005724607 -0.057250347 -0.050256222 0.997077703
1403636640863555584 3.352021456 -2.125914574 6.200931072 -0.007504525 -0.057109460 -0.050375655 0.997067928
1403636640913555456 3.361225605 -2.128659487 6.225476742 -0.008047247 -0.057282846 -0.050879087 0.997028232
1403636640963555584 3.369496822 -2.136085033 6.242609978 -0.008512340 -0.057210453 -0.051316865 0.997006059
1403636641013555456 3.376915693 -2.142524242 6.261529922 -0.007671035 -0.056761034 -0.051403459 0.997034073
1403636641063555584 3.378539085 -2.149813414 6.282708645 -0.006796109 -0.056325875 -0.050673433 0.997102499
1403636641113555456 3.393066645 -2.160157204 6.305566788 -0.006480792 -0.056137048 -0.050895251 0.997103930
1403636641163555584 3.403019667 -2.166250229 6.328889847 -0.007062565 -0.056075610 -0.051779024 0.997057915
1403636641213555456 3.409902573 -2.165247679 6.342883110 -0.005424439 -0.055185944 -0.050944362 0.997160852
1403636641263555584 3.423073053 -2.167338610 6.357231140 -0.004794253 -0.055978842 -0.049713742 0.997182012
1403636641313555456 3.430306196 -2.168672800 6.381104946 -0.005313542 -0.056597076 -0.046120472 0.997317135
1403636641363555584 3.436487198 -2.164249182 6.398287773 -0.005375080 -0.057591982 -0.041486058 0.997463346
1403636641413555456 3.438736439 -2.162441254 6.418622017 -0.005826318 -0.058085516 -0.037683427 0.997583091
1403636641463555584 3.445676565 -2.161052942 6.438922405 -0.005843408 -0.058026541 -0.037013046 0.997611523
1403636641513555456 3.459290028 -2.162798405 6.457878590 -0.005815901 -0.057807654 -0.038722616 0.997559547
1403636641563555584 3.463812351 -2.158042669 6.477949619 -0.005606333 -0.056682047 -0.040318221 0.997562110
1403636641613555456 3.474962711 -2.157610655 6.497192383 -0.005379098 -0.055599865 -0.042236082 0.997544885
1403636641663555584 3.484375000 -2.157828569 6.508557320 -0.005608477 -0.054883618 -0.044017170 0.997506320
1403636641713555456 3.486914635 -2.164194822 6.525633812 -0.005066930 -0.053881921 -0.045029633 0.997518599
1403636641763555584 3.491763115 -2.169536591 6.543453693 -0.005618002 -0.053016279 -0.046027645 0.997516513
1403636641813555456 3.501789093 -2.176820517 6.555186272 -0.004772521 -0.052909315 -0.046144042 0.997521222
1403636641863555584 3.511912346 -2.185411930 6.569164276 -0.004065291 -0.053168878 -0.046205968 0.997507691
1403636641913555456 3.518138170 -2.195816278 6.582094193 -0.003909162 -0.051762410 -0.045904189 0.997596204
1403636641963555584 3.526825428 -2.205053568 6.592900276 -0.003266528 -0.049145326 -0.044485278 0.997795105
1403636642013555456 3.535424232 -2.213509798 6.597535610 -0.001658327 -0.045223337 -0.042884111 0.998054624
1403636642063555584 3.543848991 -2.229041815 6.606722355 -0.001104812 -0.040596932 -0.041272208 0.998322248
1403636642113555456 3.554433346 -2.239842415 6.617884636 0.000008242 -0.036179338 -0.040016301 0.998543799
1403636642163555584 3.560624123 -2.251538992 6.626679420 0.000489508 -0.032125276 -0.039336644 0.998709381
1403636642213555456 3.565728426 -2.259986162 6.634872437 0.001544028 -0.028696612 -0.037803710 0.998871863
1403636642263555584 3.572467327 -2.268469334 6.644152641 0.001699310 -0.025807995 -0.036524147 0.998998046
1403636642313555456 3.583532810 -2.274230003 6.649462700 0.002094081 -0.022358449 -0.034670264 0.999146521
1403636642363555584 3.590605497 -2.277289629 6.658908844 0.002590059 -0.017441221 -0.032995488 0.999299943
1403636642413555456 3.597744703 -2.278912544 6.663996220 0.003476762 -0.013193512 -0.030739782 0.999434292
1403636642463555584 3.602908134 -2.278839111 6.672746181 0.003328931 -0.009090104 -0.029261813 0.999524891
1403636642513555456 3.613060236 -2.280351639 6.682198048 0.001760201 -0.006271551 -0.027830055 0.999591470
1403636642563555584 3.618867159 -2.278143883 6.692141533 -0.001536886 -0.002950806 -0.027864538 0.999606192
1403636642613555456 3.625931025 -2.270172596 6.696370125 -0.005302167 -0.001080918 -0.026190234 0.999642372
1403636642663555584 3.635692358 -2.265021086 6.702895164 -0.009916789 0.000388339 -0.025082102 0.999636114
1403636642713555456 3.639159679 -2.260299444 6.716445446 -0.014105518 0.002445217 -0.024719097 0.999591947
1403636642763555584 3.645961761 -2.258541584 6.725017071 -0.018247763 0.003075588 -0.024121651 0.999537766
1403636642813555456 3.655555010 -2.250513077 6.731307030 -0.020727042 0.003731553 -0.022948194 0.999514818
1403636642863555584 3.654802799 -2.252022743 6.743498802 -0.022842510 0.004452302 -0.021946236 0.999488235
1403636642913555456 3.670502424 -2.248594284 6.742800236 -0.024471605 0.003862350 -0.022239335 0.999445617
1403636642963555584 3.680390358 -2.245230913 6.748139858 -0.024397803 0.003497245 -0.021864140 0.999457061
1403636643013555456 3.682118416 -2.252764702 6.758489609 -0.024204213 0.003734255 -0.020614453 0.999487460
1403636643063555584 3.689272165 -2.259588003 6.766522884 -0.020569837 0.003530382 -0.020832775 0.999565125
1403636643113555456 3.701451063 -2.260937452 6.771619320 -0.015865086 0.002846277 -0.019452792 0.999680817
1403636643163555584 3.707593918 -2.264892340 6.781143188 -0.012518974 0.002525217 -0.018968195 0.999738514
1403636643213555456 3.712987900 -2.271731377 6.792932510 -0.010384293 0.002435335 -0.019016745 0.999762237
1403636643263555584 3.717343569 -2.275742531 6.800899506 -0.009647966 0.002261842 -0.019090956 0.999768615
1403636643313555456 3.726089954 -2.272178650 6.807878017 -0.009591814 0.002078646 -0.019431705 0.999763012
1403636643363555584 3.733845949 -2.273439407 6.822502613 -0.011597929 0.002103715 -0.019836586 0.999733686
1403636643413555456 3.743298531 -2.275967836 6.832528114 -0.013979980 0.001464179 -0.019357126 0.999713778
1403636643463555584 3.754036903 -2.277305365 6.837472439 -0.017929764 0.000761560 -0.018574046 0.999666393
1403636643513555456 3.761173964 -2.283592939 6.849573135 -0.021789525 0.000372722 -0.018695233 0.999587655
1403636643563555584 3.762776375 -2.291738033 6.856584549 -0.025322052 0.000577014 -0.019029651 0.999498010
1403636643613555456 3.774275780 -2.296668291 6.864874363 -0.028373500 0.000129010 -0.019998321 0.999397337
1403636643663555584 3.787099123 -2.304464102 6.873205185 -0.031295970 -0.000951413 -0.020980971 0.999289453
1403636643713555456 3.790832758 -2.319413662 6.884624481 -0.034334976 -0.000786342 -0.021491868 0.999178946
1403636643763555584 3.804405928 -2.335472345 6.893247604 -0.036052234 -0.001495564 -0.022676216 0.999091506
1403636643813555456 3.815311432 -2.347818375 6.904620647 -0.038663998 -0.001234678 -0.023832496 0.998967230
1403636643863555584 3.825759411 -2.360674858 6.916982651 -0.041542821 -0.001820796 -0.024506455 0.998834431
1403636643913555456 3.831894875 -2.369373322 6.931960106 -0.042986177 -0.001488336 -0.024481753 0.998774529
1403636643963555584 3.841272354 -2.385764599 6.949014187 -0.045306411 -0.001419955 -0.025946919 0.998635113
1403636644013555456 3.853072882 -2.391122341 6.966539383 -0.045760356 -0.001305196 -0.026106432 0.998610377
1403636644063555584 3.864850521 -2.403887272 6.988419056 -0.046669006 -0.001550190 -0.026751922 0.998550892
1403636644113555456 3.870689869 -2.417789936 7.011302471 -0.048165150 -0.001101236 -0.027141092 0.998469949
1403636644163555584 3.881876469 -2.422482014 7.032071114 -0.046424445 -0.001329749 -0.027468190 0.998543203
1403636644213555456 3.890379429 -2.435455322 7.060704231 -0.041665558 -0.002269819 -0.025591297 0.998801231
1403636644263555584 3.899301529 -2.445981026 7.092033863 -0.034843903 -0.003864920 -0.019818675 0.999188781
1403636644313555456 3.907787085 -2.448659420 7.115740776 -0.026042564 -0.005789686 -0.012529641 0.999565542
1403636644363555584 3.918457747 -2.459570646 7.150574684 -0.018648187 -0.007336611 -0.007159086 0.999773562
1403636644413555456 3.929675102 -2.461086273 7.179642200 -0.012689290 -0.008533858 -0.003236640 0.999877810
1403636644463555584 3.947027683 -2.460499048 7.209058762 -0.007129692 -0.009809414 0.000004346 0.999926507
1403636644513555456 3.958704710 -2.463924885 7.241247177 -0.002870475 -0.011256143 0.004704610 0.999921441
1403636644563555584 3.968363523 -2.462598562 7.273873329 -0.000280302 -0.012285332 0.009033938 0.999883711
1403636644613555456 3.991500616 -2.459144115 7.303642750 0.001502254 -0.013160583 0.009832060 0.999863923
1403636644663555584 4.002541065 -2.457619429 7.339878082 0.001915956 -0.011075867 0.005716681 0.999920487
1403636644713555456 4.025189400 -2.447821140 7.370454311 0.002963620 -0.008810372 -0.001077341 0.999956250
1403636644763555584 4.045785904 -2.438869715 7.398474693 0.002344638 -0.005654662 -0.010591402 0.999925196
1403636644813555456 4.062134743 -2.425455093 7.431636810 0.002908973 -0.001487377 -0.018074507 0.999831319
1403636644863555584 4.085259914 -2.411281586 7.464056015 0.001269900 0.001113767 -0.024148766 0.999706924
1403636644913555456 4.109195709 -2.402201891 7.494002819 -0.002276161 0.002519496 -0.026192406 0.999651134
1403636644963555584 4.133299351 -2.389593363 7.513553143 -0.004898693 0.002695090 -0.026440684 0.999634743
1403636645013555456 4.149328709 -2.382454395 7.541226387 -0.012872501 0.003621244 -0.026954480 0.999547184
1403636645063555584 4.176234722 -2.375499964 7.564667702 -0.024715435 0.003305227 -0.025289059 0.999369144
1403636645113555456 4.194114685 -2.362303257 7.587312222 -0.035623398 0.003399898 -0.023254046 0.999088883
1403636645163555584 4.216081142 -2.358778000 7.615958214 -0.046203502 0.004173918 -0.023753187 0.998640895
1403636645213555456 4.238399029 -2.362402916 7.644260883 -0.055959266 0.003744567 -0.021848992 0.998186946
1403636645263555584 4.254075527 -2.356384039 7.669166565 -0.059749044 0.004976944 -0.022941433 0.997937322
1403636645313555456 4.273689270 -2.360282660 7.697523117 -0.058955010 0.004829925 -0.021649674 0.998014152
1403636645363555584 4.291550159 -2.369208813 7.731750488 -0.054822393 0.005217811 -0.022765296 0.998222947
1403636645413555456 4.314239502 -2.377492189 7.765409946 -0.049870450 0.005520538 -0.023385407 0.998466611
1403636645463555584 4.333942413 -2.385063171 7.802773476 -0.045622133 0.005623407 -0.023483239 0.998666883
1403636645513555456 4.351955891 -2.392053127 7.838840485 -0.042097442 0.006229457 -0.023517521 0.998817265
1403636645563555584 4.374116421 -2.397239923 7.878044605 -0.040701363 0.006123338 -0.023411406 0.998878300
1403636645613555456 4.392248154 -2.402333498 7.913424969 -0.038543954 0.006710190 -0.024290035 0.998939097
1403636645663555584 4.422502995 -2.403625250 7.950328350 -0.036608171 0.005371025 -0.025271602 0.998995662
1403636645713555456 4.421523571 -2.415951729 8.001587868 -0.035852354 0.007877412 -0.024908371 0.999015570
1403636645763555584 4.448595524 -2.423750639 8.040145874 -0.034894589 0.006330931 -0.025059769 0.999056697
1403636645813555456 4.463671684 -2.435887814 8.079955101 -0.034633946 0.006162195 -0.024455568 0.999081790
1403636645863555584 4.478734493 -2.449825525 8.124211311 -0.035633635 0.006132676 -0.023363380 0.999072969
1403636645913555456 4.498354912 -2.464440346 8.167376518 -0.035868738 0.005458736 -0.022403089 0.999090433
1403636645963555584 4.515850544 -2.485773325 8.213025093 -0.031426795 0.006586007 -0.020188265 0.999280453
1403636646013555456 4.534461498 -2.504814386 8.251116753 -0.026912304 0.008652306 -0.016963448 0.999456406
1403636646063555584 4.558857441 -2.530548334 8.294074059 -0.023858063 0.011552630 -0.012009279 0.999576449
1403636646113555456 4.576423645 -2.553621531 8.338323593 -0.020104511 0.017592013 -0.006406114 0.999622583
1403636646163555584 4.591055393 -2.576776266 8.380555153 -0.016379884 0.026376210 -0.001009794 0.999517381
1403636646213555456 4.612290382 -2.601098537 8.423927307 -0.012976198 0.035657763 0.005807609 0.999262929
1403636646263555584 4.634206772 -2.619229317 8.461945534 -0.009234753 0.046355676 0.013312759 0.998793602
1403636646313555456 4.663352966 -2.644331932 8.510449409 -0.004751384 0.058228180 0.019190148 0.998107553
1403636646363555584 4.688692093 -2.664314270 8.552769661 -0.000406960 0.070454478 0.026090939 0.997173607
1403636646413555456 4.711604118 -2.682910919 8.598532677 0.003063935 0.085303538 0.029753134 0.995905936
1403636646463555584 4.732565880 -2.701529741 8.649756432 0.008161310 0.099426702 0.031162376 0.994523287
1403636646513555456 4.765741348 -2.718730688 8.686043739 0.012587859 0.110821068 0.029607151 0.993319511
1403636646563555584 4.791049480 -2.737668037 8.725414276 0.015217725 0.121474169 0.028919946 0.992056489
1403636646613555456 4.814924240 -2.756054163 8.759996414 0.014952582 0.129787028 0.029520260 0.990989566
1403636646663555584 4.846675873 -2.771492004 8.789953232 0.012984121 0.136942714 0.028510842 0.990083456
1403636646713555456 4.868160248 -2.797094107 8.829422951 0.010302228 0.143156499 0.029602546 0.989203572
1403636646763555584 4.897513390 -2.817634344 8.852432251 0.009499908 0.147166833 0.030000560 0.988610983
1403636646813555456 4.925767422 -2.840738773 8.884604454 0.009637838 0.150424615 0.030724403 0.988096952
1403636646863555584 4.950619698 -2.865398407 8.907027245 0.010080338 0.153634414 0.030366475 0.987609625
1403636646913555456 4.969480991 -2.893868446 8.936167717 0.008712180 0.155610263 0.031059766 0.987291634
1403636646963555584 5.002332687 -2.913470507 8.960057259 0.007786095 0.155980721 0.031573642 0.987224638
1403636647013555456 5.020173550 -2.939312458 8.986051559 0.005556123 0.157819241 0.031665239 0.986944556
1403636647063555584 5.043271065 -2.953996420 9.007851601 0.003637643 0.158226132 0.031674113 0.986888051
1403636647113555456 5.070682526 -2.978519678 9.034075737 -0.001047781 0.158128992 0.031257831 0.986923039
1403636647163555584 5.093600750 -2.990831614 9.055768967 -0.003364721 0.157291710 0.032010045 0.987027526
1403636647213555456 5.118023396 -3.009492636 9.081183434 -0.006001589 0.157686055 0.030827153 0.986989737
1403636647263555584 5.139842987 -3.022830486 9.105696678 -0.005675856 0.156882897 0.031840075 0.987087488
1403636647313555456 5.162948132 -3.039590597 9.127651215 -0.004910730 0.155771375 0.032723844 0.987238705
1403636647363555584 5.186235428 -3.049588680 9.152406693 -0.002892084 0.154389784 0.033555906 0.987435818
1403636647413555456 5.209836960 -3.064992905 9.176704407 -0.001438199 0.153558195 0.033689149 0.987564087
1403636647463555584 5.236803055 -3.071190119 9.197761536 0.000960358 0.151554033 0.034742262 0.987837791
1403636647513555456 5.257262230 -3.080853701 9.220573425 0.004414087 0.150152668 0.035180457 0.988026857
1403636647563555584 5.282858849 -3.091530085 9.243320465 0.008725616 0.148276985 0.036720775 0.988225341
1403636647613555456 5.304550171 -3.099580765 9.263240814 0.014317893 0.146757066 0.039161127 0.988293350
1403636647663555584 5.333306313 -3.108791590 9.279454231 0.015385369 0.147121832 0.039811850 0.988197088
1403636647713555456 5.356538773 -3.114553928 9.297917366 0.014494112 0.148521677 0.038919147 0.988036692
1403636647763555584 5.385309696 -3.123977900 9.310751915 0.012292920 0.149565935 0.038165633 0.987938404
1403636647813555456 5.409605503 -3.142823458 9.328304291 0.010298040 0.151910752 0.036598340 0.987662733
1403636647863555584 5.437845230 -3.150831461 9.342810631 0.008365329 0.155001745 0.036832128 0.987191916
1403636647913555456 5.464293003 -3.152991772 9.349466324 0.008377955 0.159468323 0.037102047 0.986470044
1403636647963555584 5.490154266 -3.158121586 9.360042572 0.008206520 0.165219903 0.038832061 0.985457838
1403636648013555456 5.516550541 -3.162603617 9.370707512 0.007686426 0.172923401 0.040585943 0.984068692
1403636648063555584 5.545193195 -3.162850618 9.383544922 0.007279024 0.182596385 0.043377947 0.982203603
1403636648113555456 5.575091839 -3.164434910 9.397548676 0.006570528 0.193450391 0.046691377 0.979976356
1403636648163555584 5.603208542 -3.151264668 9.416074753 0.007712868 0.205833346 0.050938904 0.977229953
1403636648213555456 5.638005733 -3.141212702 9.425397873 0.008541229 0.217405856 0.054700125 0.974509954
1403636648263555584 5.658863544 -3.145329714 9.436251640 0.008390604 0.230621666 0.059593391 0.971180677
1403636648313555456 5.687020779 -3.126978159 9.437128067 0.009264870 0.242947549 0.063324764 0.967925966
1403636648363555584 5.708863258 -3.117412567 9.449735641 0.010081179 0.256642580 0.067645356 0.964083552
1403636648413555456 5.744575024 -3.106604815 9.472645760 0.009953444 0.270637304 0.072959520 0.959861100
1403636648463555584 5.780003548 -3.113723278 9.460197449 0.008410034 0.282064319 0.077408843 0.956230521
1403636648513555456 5.798439503 -3.104439259 9.469253540 0.008677698 0.296159267 0.083465539 0.951445162
1403636648563555584 5.834988594 -3.090886593 9.490983009 0.008849862 0.307579428 0.086985797 0.947496712
1403636648613555456 5.879546165 -3.081883430 9.500039101 0.008877363 0.317033887 0.089552283 0.944135129
1403636648663555584 5.897043228 -3.076377392 9.487447739 0.006569237 0.325480938 0.091530733 0.941085041
1403636648713555456 5.906020164 -3.048099518 9.485822678 0.006317726 0.333451241 0.094592847 0.937988579
1403636648763555584 5.935541153 -3.064548492 9.474225998 0.001243116 0.338321418 0.096493833 0.936069489
1403636648813555456 5.967623234 -3.067522764 9.478901863 -0.006849548 0.342147648 0.099863172 0.934299409
1403636648863555584 5.987509727 -3.064732075 9.483839035 -0.013267978 0.345075071 0.103528649 0.932753444
1403636648913555456 6.011505127 -3.066674948 9.467391014 -0.020124778 0.346489310 0.105004340 0.931941152
1403636648963555584 6.020957947 -3.072440386 9.474933624 -0.025314983 0.349537373 0.105525598 0.930616558
1403636649013555456 6.043423176 -3.061307907 9.485548019 -0.024870737 0.350770473 0.105888940 0.930123150
1403636649063555584 6.077621460 -3.086071491 9.486228943 -0.023041835 0.351479948 0.103688434 0.930150330
1403636649113555456 6.100812912 -3.085940123 9.480768204 -0.015039556 0.352548212 0.101799443 0.930118501
1403636649163555584 6.126773357 -3.096583366 9.462982178 -0.007306124 0.352053642 0.099852182 0.930609703
1403636649213555456 6.166880131 -3.091275215 9.450243950 0.001611166 0.350445151 0.097284555 0.931515574
1403636649263555584 6.192317009 -3.089226246 9.454298019 0.008171733 0.350784898 0.095184386 0.931570232
1403636649313555456 6.199898243 -3.128867149 9.454798698 0.008052115 0.352118850 0.095661238 0.931019008
1403636649363555584 6.232114792 -3.126765966 9.433687210 0.008108266 0.348994195 0.093621172 0.932401419
1403636649413555456 6.262763977 -3.175077438 9.443817139 0.003095479 0.348424435 0.092701763 0.932736397
1403636649463555584 6.283385277 -3.194818020 9.427369118 -0.000356698 0.345754147 0.093267955 0.933678210
1403636649513555456 6.307396889 -3.198184013 9.433135033 0.000957391 0.344053239 0.091933534 0.934438169
1403636649563555584 6.332428455 -3.243597984 9.422155380 0.001770971 0.341826469 0.090608798 0.935383081
1403636649613555456 6.351119041 -3.253531933 9.404676437 0.006636926 0.340757221 0.090812348 0.935731590
1403636649663555584 6.373280525 -3.284026623 9.401716232 0.010519622 0.341572493 0.093208082 0.935163021
1403636649713555456 6.399527073 -3.294986486 9.402267456 0.014098691 0.344064713 0.093854040 0.934137106
1403636649763555584 6.409000874 -3.334899664 9.395038605 0.014440021 0.349143445 0.095286801 0.932100177
1403636649813555456 6.431650639 -3.346622229 9.377844810 0.015131382 0.352350354 0.095265381 0.930883825
1403636649863555584 6.445574760 -3.353081703 9.382232666 0.016899191 0.356753767 0.094882444 0.929213941
1403636649913555456 6.463939667 -3.356176376 9.370300293 0.018556848 0.360352546 0.094156995 0.927866459
1403636649963555584 6.494034767 -3.365682602 9.355276108 0.018683290 0.362431586 0.093293950 0.927141070
1403636650013555456 6.511610508 -3.377844572 9.347328186 0.018636435 0.365477949 0.093951173 0.925878882
1403636650063555584 6.525503159 -3.400934219 9.329148293 0.017581463 0.367693126 0.095107421 0.924903870
1403636650113555456 6.528285027 -3.376551390 9.336581230 0.020475553 0.372780830 0.095552370 0.922759414
1403636650163555584 6.521728516 -3.366237879 9.328343391 0.022430509 0.379778773 0.097588122 0.919642031
1403636650213555456 6.514543056 -3.324517488 9.339949608 0.024486132 0.389172733 0.099209093 0.915479422
1403636650263555584 6.500968933 -3.326207876 9.381089211 0.023942653 0.403015703 0.100567445 0.909335613
1403636650313555456 6.540269852 -3.351037264 9.365982056 0.020909652 0.411631018 0.106225632 0.904897153
1403636650363555584 6.444280148 -3.332266331 9.432145119 0.022622662 0.432814211 0.112074547 0.894203186
1403636650413555456 6.436574459 -3.392181158 9.438169479 0.015316835 0.446978003 0.116367109 0.886811554
1403636650463555584 6.416604996 -3.405939341 9.437606812 0.012637259 0.461783469 0.126197338 0.877878428
1403636650513555456 6.562666893 -3.290613413 9.312505722 0.015496682 0.459013462 0.128592446 0.878937125
1403636650563555584 6.683450699 -3.332142830 9.221313477 0.007287670 0.460002840 0.133860737 0.877738893
1403636650613555456 6.695715427 -3.328800201 9.202619553 0.003942958 0.468004286 0.138307005 0.872827351
1403636650663555584 6.695180416 -3.315428257 9.203030586 0.003024888 0.475647569 0.141680822 0.868145585
1403636650713555456 6.714085579 -3.297413588 9.181199074 0.001501629 0.481303871 0.143694907 0.864694238
1403636650763555584 6.713331223 -3.295539141 9.187844276 0.000751380 0.487540483 0.146381021 0.860741735
1403636650813555456 6.716230869 -3.289417028 9.180128098 0.001285099 0.492116362 0.147562832 0.857930660
1403636650863555584 6.724379539 -3.285281181 9.178390503 0.003172859 0.496695220 0.147755176 0.855249763
1403636650913555456 6.760697365 -3.285102367 9.138275146 0.005577487 0.497610509 0.145820498 0.855037451
1403636650963555584 6.752610683 -3.271774054 9.126528740 0.010032449 0.500048041 0.143726543 0.853928566
1403636651013555456 6.750797272 -3.275067091 9.127904892 0.012116869 0.502693474 0.142045155 0.852628648
1403636651063555584 6.762111664 -3.273142338 9.098121643 0.013567799 0.502693951 0.141721055 0.852660418
1403636651113555456 6.732818127 -3.253773689 9.111883163 0.017139817 0.505486310 0.139792442 0.851262510
1403636651163555584 6.761291504 -3.256316185 9.068883896 0.016415132 0.502662718 0.139861852 0.852935731
1403636651213555456 6.756802559 -3.262214184 9.068290710 0.015199787 0.502990007 0.140960053 0.852584422
1403636651263555584 6.757605553 -3.273632050 9.052375793 0.012426053 0.502052426 0.142547101 0.852918148
1403636651313555456 6.766796589 -3.286206722 9.042213440 0.009093210 0.500803709 0.142904162 0.853634238
1403636651363555584 6.772532463 -3.279709339 9.014741898 0.006932726 0.498493373 0.143320158 0.854936004
1403636651413555456 6.788256645 -3.274015903 8.971605301 0.006021996 0.495144606 0.142976418 0.856944203
1403636651463555584 6.790898323 -3.269528866 8.952663422 0.005285498 0.493327260 0.142495424 0.858076572
1403636651513555456 6.780999184 -3.271804094 8.941444397 0.005705182 0.492655724 0.141360506 0.858647227
1403636651563555584 6.782365799 -3.274910450 8.931178093 0.007834382 0.491874635 0.140422881 0.859231889
1403636651613555456 6.775932312 -3.266093016 8.915873528 0.011922243 0.491400152 0.138255015 0.859807730
1403636651663555584 6.780753136 -3.266217709 8.901908875 0.014626522 0.490184665 0.136769503 0.860696912
1403636651713555456 6.777860165 -3.266379833 8.893264771 0.016973414 0.489868224 0.137090355 0.860782981
1403636651763555584 6.788331985 -3.260241032 8.872580528 0.020175863 0.489558190 0.139101878 0.860567510
1403636651813555456 6.777605057 -3.247774601 8.856533051 0.024819873 0.490996450 0.143961832 0.858825624
1403636651863555584 6.781352043 -3.259975910 8.842263222 0.027382545 0.494215190 0.148720935 0.856086254
1403636651913555456 6.775105476 -3.234819412 8.823605537 0.030771947 0.499361396 0.151760533 0.852443576
1403636651963555584 6.775943756 -3.243477345 8.814882278 0.031607121 0.506807685 0.156534210 0.847138703
1403636652013555456 6.792956352 -3.215732574 8.765958786 0.032859445 0.513166368 0.157870740 0.843004942
1403636652063555584 6.783811569 -3.200643539 8.738603592 0.031475071 0.523708820 0.161730126 0.835812032
1403636652113555456 6.789657593 -3.189374924 8.715501785 0.027140422 0.536055565 0.163885027 0.827677190
1403636652163555584 6.765534401 -3.173512459 8.711891174 0.023002693 0.551551402 0.166561022 0.817018569
1403636652213555456 6.777379036 -3.163503170 8.662770271 0.017330175 0.564575195 0.173089057 0.806842387
1403636652263555584 6.755496025 -3.151584148 8.711767197 0.013046389 0.582452595 0.178808242 0.792847037
1403636652313555456 6.716742039 -3.115695953 8.674726486 0.008747881 0.595853865 0.187996358 0.780729771
1403636652363555584 6.775330544 -3.107277870 8.602450371 0.001634056 0.605000377 0.195347190 0.771888196
1403636652413555456 6.727607727 -3.099504471 8.613440514 -0.001483388 0.618930161 0.203027323 0.758751035
1403636652463555584 6.720372677 -3.078437805 8.633649826 -0.002095475 0.629767179 0.210030809 0.747847557
1403636652513555456 6.687936783 -3.066523552 8.555376053 -0.005917611 0.635542095 0.212405056 0.742250204
1403636652563555584 6.737183094 -3.007032871 8.513652802 -0.007544557 0.639443576 0.216886654 0.737573802
1403636652613555456 6.735836983 -2.988663912 8.496600151 -0.011136276 0.644494712 0.220980003 0.731895089
1403636652663555584 6.709738731 -3.012782335 8.518936157 -0.016595144 0.650315344 0.226281062 0.724990606
1403636652713555456 6.717669487 -2.975308895 8.472437859 -0.019477969 0.653619051 0.225955755 0.722043395
1403636652763555584 6.729572296 -2.947416782 8.411632538 -0.019863248 0.653302193 0.226936921 0.722011983
1403636652813555456 6.726666451 -2.951361179 8.407783508 -0.020164084 0.656430840 0.227901116 0.718855381
1403636652863555584 6.725655556 -2.946985483 8.366308212 -0.018966779 0.656895280 0.228884384 0.718150914
1403636652913555456 6.738401413 -2.950496435 8.354058266 -0.017938294 0.657975793 0.227508590 0.717625201
1403636652963555584 6.734684944 -2.956557989 8.337837219 -0.016821578 0.659783959 0.225050285 0.716766715
1403636653013555456 6.757662296 -2.950612545 8.281888008 -0.015520831 0.658034444 0.223708004 0.718821585
1403636653063555584 6.777731895 -2.939801931 8.258601189 -0.014666447 0.658819377 0.219748870 0.719341576
1403636653113555456 6.781194210 -2.934694290 8.235074997 -0.011598516 0.658975542 0.217753410 0.719861209
1403636653163555584 6.790870190 -2.920845032 8.207470894 -0.007802217 0.658605456 0.214504346 0.721225202
1403636653213555456 6.792273521 -2.905959606 8.192564011 -0.004873845 0.659122169 0.208023727 0.722675860
1403636653263555584 6.817246437 -2.902669191 8.161190033 -0.001701152 0.658298433 0.202937081 0.724883974
1403636653313555456 6.830787659 -2.896694183 8.142656326 0.001236748 0.658243835 0.198878303 0.726058483
1403636653363555584 6.829606533 -2.883797646 8.123056412 0.003644546 0.657540560 0.195853725 0.727508366
1403636653413555456 6.846771240 -2.876968384 8.107090950 0.004190849 0.656645238 0.193323150 0.728989482
1403636653463555584 6.851454735 -2.873873234 8.083181381 0.004065096 0.655103922 0.192922756 0.730481446
1403636653513555456 6.866609573 -2.875395298 8.053114891 0.003137722 0.653109729 0.192660734 0.732338488
1403636653563555584 6.870059967 -2.875844717 8.037223816 0.003133649 0.651808918 0.192979127 0.733412862
1403636653613555456 6.870579243 -2.875895023 8.018231392 0.005132057 0.650996745 0.192208052 0.734324872
1403636653663555584 6.874611378 -2.871603489 7.997514725 0.007061102 0.650704861 0.189354792 0.735308170
1403636653713555456 6.885368347 -2.871360779 7.961977482 0.008840396 0.649672627 0.187657371 0.736635566
1403636653763555584 6.886048317 -2.878574371 7.955865860 0.010602675 0.650227785 0.185957864 0.736553490
1403636653813555456 6.905570984 -2.874196053 7.923980713 0.011409415 0.649407983 0.184644699 0.737594366
1403636653863555584 6.909700394 -2.868213654 7.906223297 0.012105597 0.649640977 0.183114976 0.737759411
1403636653913555456 6.916124344 -2.868947268 7.893735886 0.012273200 0.649670839 0.183281556 0.737688959
1403636653963555584 6.906655312 -2.852057457 7.868403435 0.012449278 0.648691297 0.184503317 0.738243282
1403636654013555456 6.909349442 -2.845241785 7.858377457 0.012648008 0.648170173 0.187407523 0.737966061
1403636654063555584 6.908086777 -2.833826065 7.836237907 0.012984675 0.647009850 0.189714745 0.738388777
1403636654113555456 6.906319618 -2.826186180 7.825828075 0.013794540 0.647698760 0.191392675 0.737336338
1403636654163555584 6.912337780 -2.820071220 7.803867817 0.015185628 0.649375439 0.192547962 0.735531271
1403636654213555456 6.910441875 -2.808904648 7.781363010 0.016201952 0.652188778 0.192973390 0.732904196
1403636654263555584 6.910364628 -2.804136753 7.752038479 0.014296068 0.655714452 0.193951875 0.729531944
1403636654313555456 6.908813477 -2.798474789 7.747319221 0.013200763 0.661252439 0.195565477 0.724102974
1403636654363555584 6.900883198 -2.790413618 7.724155903 0.011391225 0.666259766 0.197936863 0.718880475
1403636654413555456 6.891923904 -2.793100595 7.716915131 0.008985428 0.672711372 0.200900659 0.712051630
1403636654463555584 6.884884834 -2.779516697 7.683015823 0.008321749 0.678438067 0.204055414 0.705701053
1403636654513555456 6.883804798 -2.780877113 7.661705494 0.006670454 0.685634375 0.206334129 0.698059618
1403636654563555584 6.875609398 -2.782681942 7.637665272 0.005211722 0.692869544 0.208912611 0.690116048
1403636654613555456 6.866940975 -2.783661604 7.623419285 0.004121114 0.698795557 0.213402331 0.682735145
1403636654663555584 6.859792709 -2.790082216 7.597768784 0.004308011 0.702859163 0.219941825 0.676458418
1403636654713555456 6.844486237 -2.783539534 7.580016136 0.003547088 0.706945598 0.222665146 0.671293914
1403636654763555584 6.842736244 -2.786582470 7.567368031 0.002095447 0.710744619 0.225825861 0.666213453
1403636654813555456 6.828509331 -2.782944441 7.546653748 0.001392897 0.714157939 0.227647752 0.661931276
1403636654863555584 6.822794914 -2.779706001 7.539234638 0.000255416 0.717497170 0.228724927 0.657938123
1403636654913555456 6.814809799 -2.776198864 7.508460522 -0.000488418 0.719436705 0.228579387 0.655867338
1403636654963555584 6.812401295 -2.767558098 7.487136841 0.001764568 0.722452044 0.226247653 0.653354406
1403636655013555456 6.802341461 -2.752413750 7.472512722 0.006075629 0.725337803 0.222762927 0.651325524
1403636655063555584 6.795254707 -2.743494272 7.463217258 0.009663904 0.727630198 0.219657093 0.649778187
1403636655113555456 6.788779259 -2.738445520 7.442861557 0.012412241 0.728920400 0.218463808 0.648686767
1403636655163555584 6.780116081 -2.729182720 7.432024479 0.014457381 0.730498910 0.215826124 0.647751033
1403636655213555456 6.768776894 -2.720422745 7.416332245 0.016997857 0.731071413 0.214756161 0.647399008
1403636655263555584 6.755950928 -2.714644909 7.406980991 0.019658219 0.732618451 0.215240523 0.645411015
1403636655313555456 6.753328800 -2.698990107 7.392396450 0.021072285 0.734526217 0.215196893 0.643208802
1403636655363555584 6.744608879 -2.689054251 7.374544144 0.023147289 0.736659706 0.216381252 0.640293598
1403636655413555456 6.727338791 -2.677863121 7.358356953 0.025297370 0.738794088 0.217536032 0.637355030
1403636655463555584 6.709411621 -2.673561573 7.350009441 0.025490887 0.742215037 0.218118697 0.633159757
1403636655513555456 6.690111160 -2.657237530 7.333630085 0.025851332 0.745682299 0.219388321 0.628616214
1403636655563555584 6.672778130 -2.656124592 7.323050022 0.023236800 0.748743594 0.224549964 0.623233914
1403636655613555456 6.650675774 -2.652356148 7.314274311 0.019498246 0.751894534 0.231722862 0.616910815
1403636655663555584 6.633085728 -2.637813091 7.290853024 0.017761430 0.753953218 0.239813715 0.611333430
1403636655713555456 6.618631363 -2.635620117 7.274158001 0.014922680 0.755711555 0.247031212 0.606343865
1403636655763555584 6.590425491 -2.615945816 7.264025688 0.012820808 0.758729219 0.251374811 0.600813091
1403636655813555456 6.566979885 -2.602050781 7.255614281 0.011883200 0.762497723 0.255346984 0.594351709
1403636655863555584 6.542354584 -2.583620548 7.250252724 0.011871505 0.766991556 0.259796768 0.586590767
1403636655913555456 6.534231186 -2.557529449 7.231852055 0.012216729 0.771864414 0.263331532 0.578560710
1403636655963555584 6.511391640 -2.534029007 7.217371941 0.013193290 0.777267814 0.266176850 0.569939077
1403636656013555456 6.491547585 -2.515726566 7.205597878 0.014652094 0.782077909 0.268528849 0.562166929
1403636656063555584 6.469973564 -2.500469446 7.193500996 0.014640989 0.786983073 0.269056588 0.555024147
1403636656113555456 6.447409630 -2.483629227 7.173194885 0.013217121 0.790527761 0.269987077 0.549543619
1403636656163555584 6.427633286 -2.465483427 7.152890682 0.011916452 0.793739915 0.270179659 0.544828355
1403636656213555456 6.409252167 -2.456322193 7.132272720 0.008635176 0.796339571 0.271256655 0.540544748
1403636656263555584 6.384269714 -2.446869373 7.118564606 0.006766903 0.798567533 0.271298826 0.537253261
1403636656313555456 6.369275093 -2.441608906 7.092595100 0.004720467 0.799485922 0.272933275 0.535077095
1403636656363555584 6.353066444 -2.433612585 7.065579891 0.005089653 0.799793065 0.274187446 0.533972204
1403636656413555456 6.332781792 -2.429170847 7.043729305 0.003609229 0.800266266 0.274008006 0.533367038
1403636656463555584 6.312576771 -2.434607506 7.018472672 0.003630789 0.800355136 0.274969697 0.532738268
1403636656513555456 6.296838760 -2.433219194 6.990927219 0.002691433 0.800336421 0.274758130 0.532881260
1403636656563555584 6.281861305 -2.433768749 6.960770607 0.001948872 0.800456941 0.273292154 0.533456981
1403636656613555456 6.264757633 -2.432967663 6.935398579 0.001974936 0.800849140 0.270486444 0.534297466
1403636656663555584 6.251323700 -2.437689304 6.911469936 0.004467952 0.801863074 0.267117679 0.534456491
1403636656713555456 6.237995148 -2.431803226 6.881851673 0.009358378 0.803155780 0.260509849 0.535712361
1403636656763555584 6.223146439 -2.424624681 6.854722500 0.013448023 0.804512739 0.253407687 0.536994338
1403636656813555456 6.206823349 -2.424875498 6.827537060 0.015372003 0.805262744 0.248812646 0.537966490
1403636656863555584 6.194232941 -2.419245005 6.804906845 0.015115266 0.806083798 0.244711310 0.538624883
1403636656913555456 6.174091339 -2.410973072 6.783932686 0.016743997 0.806184828 0.242026344 0.539637685
1403636656963555584 6.159166336 -2.398833752 6.756552219 0.018187461 0.805836916 0.240015864 0.541006863
1403636657013555456 6.144397259 -2.388920546 6.735779285 0.020331345 0.805522442 0.239498034 0.541627944
1403636657063555584 6.125483990 -2.380836964 6.721273422 0.022451490 0.805199265 0.239577234 0.541989625
1403636657113555456 6.105058670 -2.361972332 6.699486256 0.024461061 0.804277420 0.239612743 0.543254137
1403636657163555584 6.085959435 -2.348703146 6.677614689 0.026944557 0.803340077 0.240777552 0.544008076
1403636657213555456 6.060341358 -2.331415176 6.654938221 0.028890051 0.801993251 0.242088467 0.545312166
1403636657263555584 6.043856621 -2.319138050 6.637544632 0.027871922 0.801223934 0.244809002 0.545281529
1403636657313555456 6.012786865 -2.310846567 6.619700909 0.027317734 0.800211608 0.247576147 0.545546651
1403636657363555584 5.985657692 -2.302818775 6.598422527 0.026430959 0.798851669 0.251351595 0.545856833
1403636657413555456 5.960301876 -2.292601109 6.577053070 0.025381250 0.797272325 0.256897479 0.545633912
1403636657463555584 5.930614471 -2.286338329 6.556035995 0.023787960 0.795253098 0.263217121 0.545640349
1403636657513555456 5.905257225 -2.271288872 6.536970139 0.022294214 0.794065773 0.267026693 0.545581520
1403636657563555584 5.876276016 -2.254822493 6.517158985 0.020554963 0.793341517 0.269804001 0.545337081
1403636657613555456 5.850416660 -2.240892887 6.493826866 0.019119572 0.793065369 0.271053463 0.545171440
1403636657663555584 5.821187973 -2.226191998 6.469828129 0.019025020 0.792788625 0.271542639 0.545333743
1403636657713555456 5.788574219 -2.213204384 6.454027653 0.019330239 0.793390095 0.271130681 0.544652700
1403636657763555584 5.766791821 -2.193317890 6.425441742 0.020088525 0.794000804 0.271915048 0.543342948
1403636657813555456 5.738530636 -2.169979095 6.397753239 0.021659836 0.794173241 0.273227245 0.542371273
1403636657863555584 5.709974289 -2.154863596 6.382980347 0.024070146 0.794336677 0.277246982 0.539985240
1403636657913555456 5.682413578 -2.138864279 6.359434128 0.025631184 0.793676496 0.282360017 0.538231790
1403636657963555584 5.654467583 -2.116773605 6.332470417 0.026199365 0.793336987 0.285350919 0.537126541
1403636658013555456 5.626862049 -2.099708557 6.307427406 0.025195232 0.794149458 0.285922885 0.535667717
1403636658063555584 5.601348877 -2.082768440 6.275555611 0.021515558 0.794871151 0.285945475 0.534744918
1403636658113555456 5.571212769 -2.066926003 6.248414040 0.016501369 0.797351182 0.281644374 0.533512175
1403636658163555584 5.543181419 -2.057998896 6.210403919 0.012448574 0.798386514 0.280438006 0.532708704
1403636658213555456 5.512682915 -2.046835899 6.171326160 0.009215411 0.799380779 0.278632283 0.532230735
1403636658263555584 5.491192818 -2.028182268 6.136878490 0.004262298 0.801486015 0.274722457 0.531158507
1403636658313555456 5.466332436 -2.013035536 6.098294735 0.001298430 0.802168250 0.273570925 0.530738473
1403636658363555584 5.440523624 -1.995555401 6.065381050 -0.000473090 0.802932680 0.272897542 0.529929936
1403636658413555456 5.416827202 -1.985796452 6.028124809 -0.003174559 0.803159893 0.273465931 0.529282928
1403636658463555584 5.393298149 -1.964786887 5.995904446 -0.006349385 0.804241955 0.271645099 0.528548479
1403636658513555456 5.370770931 -1.945524931 5.954257965 -0.009269610 0.804267704 0.270681262 0.528960407
1403636658563555584 5.352985382 -1.927162647 5.928225517 -0.012924482 0.806275606 0.267914385 0.527232826
1403636658613555456 5.328106403 -1.902990580 5.889888287 -0.015905857 0.806623936 0.264976889 0.528102279
1403636658663555584 5.315621853 -1.889232993 5.856771469 -0.018043654 0.807166696 0.264831573 0.527276635
1403636658713555456 5.295345783 -1.870587111 5.825653553 -0.018274838 0.807845950 0.263184845 0.527052820
1403636658763555584 5.279444695 -1.846267223 5.802474976 -0.018874956 0.809717178 0.259331286 0.526069462
1403636658813555456 5.264559746 -1.828754663 5.767043114 -0.020994015 0.810849607 0.255127519 0.526300430
1403636658863555584 5.251023293 -1.807957768 5.740266800 -0.020704886 0.812372983 0.251007199 0.525943756
1403636658913555456 5.236190796 -1.786332130 5.708184719 -0.016554167 0.812733948 0.249468997 0.526264727
1403636658963555584 5.221973419 -1.762121677 5.678811550 -0.011079530 0.812629104 0.248412386 0.527069569
1403636659013555456 5.210340023 -1.743147016 5.658657074 -0.006480761 0.813114107 0.248303264 0.526449323
1403636659063555584 5.196363449 -1.726790071 5.635558605 -0.002341803 0.813433230 0.246916920 0.526643157
1403636659113555456 5.182825565 -1.707530022 5.616760731 0.000378357 0.813867629 0.246381268 0.526227772
1403636659163555584 5.171217442 -1.691526413 5.600660324 0.002906393 0.814272046 0.246559247 0.525510252
1403636659213555456 5.157787323 -1.655673504 5.576766968 0.004735964 0.814285934 0.243694991 0.526809990
1403636659263555584 5.141619682 -1.633031726 5.561442852 0.006167590 0.814356863 0.244066209 0.526513696
1403636659313555456 5.126109600 -1.614228725 5.545701981 0.003644218 0.813821614 0.245727256 0.526592016
1403636659363555584 5.111349106 -1.593167067 5.522047997 0.002920600 0.812271535 0.248946667 0.527476966
1403636659413555456 5.097174644 -1.578585863 5.511234283 -0.001263202 0.811506927 0.252486169 0.526977897
1403636659463555584 5.082730770 -1.566531420 5.497368336 -0.004376916 0.810264707 0.256694525 0.526839554
1403636659513555456 5.063275337 -1.544725418 5.478007317 -0.005891989 0.810063303 0.255650252 0.527641714
1403636659563555584 5.050429821 -1.542225599 5.469249249 -0.005945065 0.810083747 0.258266836 0.526333630
1403636659613555456 5.034510612 -1.529601336 5.451825619 -0.005980453 0.810799301 0.256292343 0.526196659
1403636659663555584 5.023540497 -1.514839411 5.434415340 -0.005370447 0.811561704 0.254849613 0.525728524
1403636659713555456 5.009409904 -1.500987649 5.420703411 -0.004703826 0.812346756 0.253608406 0.525122285
1403636659763555584 4.998156548 -1.489011526 5.410443783 -0.004218308 0.813535750 0.252555311 0.523791611
1403636659813555456 4.983230114 -1.469395041 5.401349068 -0.003849468 0.814224362 0.251707613 0.523132086
1403636659863555584 4.972131729 -1.455164671 5.391751289 -0.003283366 0.814419329 0.252567619 0.522417426
1403636659913555456 4.957533836 -1.434636474 5.384344578 -0.003977229 0.814431548 0.253558427 0.521913409
1403636659963555584 4.945395470 -1.416761041 5.381342411 -0.006928786 0.814275265 0.257035583 0.520423412
1403636660013555456 4.931996346 -1.396151781 5.374711990 -0.009441879 0.813455343 0.260490984 0.519947827
1403636660063555584 4.920961380 -1.374482632 5.372454643 -0.011644900 0.812872171 0.264302731 0.518890560
1403636660113555456 4.908900261 -1.355528355 5.364424229 -0.014575697 0.811616302 0.268110007 0.518828988
1403636660163555584 4.897958755 -1.333284855 5.361066818 -0.016958872 0.811005533 0.270276636 0.518587410
1403636660213555456 4.884092331 -1.310768485 5.352749348 -0.016890200 0.810327590 0.271412909 0.519055843
1403636660263555584 4.879348755 -1.289042473 5.354700089 -0.019369341 0.809967160 0.274106115 0.518115699
1403636660313555456 4.870626450 -1.268224359 5.347775936 -0.021837838 0.808476388 0.277128637 0.518737614
1403636660363555584 4.867214680 -1.249438047 5.351265907 -0.026653728 0.807306886 0.282711446 0.517319441
1403636660413555456 4.862359047 -1.233387709 5.345938206 -0.030245654 0.805289626 0.288155705 0.517262101
1403636660463555584 4.858632088 -1.218575835 5.340526581 -0.031719036 0.804181159 0.291249692 0.517165422
1403636660513555456 4.860006332 -1.204312801 5.338295937 -0.032750595 0.804362416 0.290550828 0.517212391
1403636660563555584 4.861732483 -1.188927889 5.333616734 -0.031523284 0.805708587 0.286568552 0.517415166
1403636660613555456 4.867854595 -1.177272320 5.331398964 -0.027743297 0.807963252 0.280670732 0.517348588
1403636660663555584 4.872436523 -1.158240676 5.322712898 -0.024650248 0.810360730 0.272259951 0.518249333
1403636660713555456 4.883631706 -1.145560503 5.318857193 -0.022428911 0.812947392 0.264840841 0.518143475
1403636660763555584 4.889318943 -1.123395443 5.321477413 -0.020608068 0.815902472 0.256289959 0.517874420
1403636660813555456 4.899947643 -1.106536388 5.316576481 -0.022186115 0.817728460 0.249404237 0.518290877
1403636660863555584 4.906725883 -1.085554242 5.317534924 -0.023280539 0.819194674 0.243287519 0.518834531
1403636660913555456 4.917562485 -1.063415051 5.323129654 -0.024234820 0.820541859 0.239543080 0.518404126
1403636660963555584 4.929607391 -1.044120908 5.328616619 -0.021913730 0.820707321 0.239009783 0.518491566
1403636661013555456 4.938604355 -1.025571585 5.335230350 -0.018827450 0.820232213 0.240193874 0.518817425
1403636661063555584 4.953177452 -1.004308462 5.343902111 -0.015213107 0.819969416 0.241439402 0.518773377
1403636661113555456 4.963925362 -0.983294368 5.354205608 -0.011605673 0.819525778 0.242381826 0.519127965
1403636661163555584 4.973205090 -0.964576721 5.363359928 -0.008233984 0.818879783 0.244216457 0.519351900
1403636661213555456 4.982625008 -0.939599514 5.381194115 -0.004775713 0.819280744 0.243160397 0.519258320
1403636661263555584 4.994509697 -0.920313656 5.394059181 -0.003031813 0.818847895 0.244794086 0.519186616
1403636661313555456 5.000017166 -0.906449378 5.407679081 -0.001550963 0.818654954 0.244977742 0.519410670
1403636661363555584 5.009049416 -0.894933403 5.419883251 -0.001505004 0.818365753 0.245293126 0.519717634
1403636661413555456 5.018043041 -0.881318152 5.434165478 -0.001240544 0.818492830 0.244889989 0.519708395
1403636661463555584 5.027078152 -0.875279307 5.448170662 -0.000907891 0.818351030 0.245766521 0.519518614
1403636661513555456 5.031287193 -0.863559663 5.464334965 -0.000903543 0.817663670 0.246827289 0.520097613
1403636661563555584 5.034964561 -0.862207592 5.473317146 -0.000923117 0.816251874 0.249433115 0.521071196
1403636661613555456 5.043328762 -0.855229437 5.493435860 0.000961746 0.815745950 0.251478225 0.520880222
1403636661663555584 5.049251080 -0.854633391 5.511053085 0.002454293 0.815567791 0.251819104 0.520989656
1403636661713555456 5.052565575 -0.856618583 5.525628090 0.002757563 0.815763175 0.250954926 0.521099210
1403636661763555584 5.060723782 -0.857209802 5.539056301 0.008429111 0.815153360 0.252311319 0.521337569
1403636661813555456 5.062991142 -0.861110628 5.552114487 0.013569122 0.813822627 0.254411906 0.522286534
1403636661863555584 5.065906525 -0.867016494 5.567877769 0.016753789 0.813593864 0.254580885 0.522468209
1403636661913555456 5.066740036 -0.875322878 5.580280781 0.018384896 0.813271940 0.254752338 0.522830725
1403636661963555584 5.068222046 -0.881496727 5.593429565 0.019689623 0.813006699 0.254362822 0.523385108
1403636662013555456 5.065209389 -0.891965508 5.603580475 0.019406378 0.812915742 0.253915340 0.523754179
1403636662063555584 5.062817574 -0.901406944 5.618689537 0.019050075 0.813533843 0.252332807 0.523572326
1403636662113555456 5.060644150 -0.917038441 5.627892971 0.018439077 0.813361704 0.252266765 0.523893356
1403636662163555584 5.053800583 -0.919671357 5.639508247 0.015978109 0.813744605 0.251026392 0.523975372
1403636662213555456 5.049835682 -0.935199797 5.654032707 0.010507570 0.814461410 0.250274181 0.523359478
1403636662263555584 5.040652752 -0.941367984 5.670870781 0.005060679 0.815523446 0.247996345 0.522870719
1403636662313555456 5.040112019 -0.943406761 5.679102898 0.001137353 0.816022456 0.247587815 0.522308767
1403636662363555584 5.033807755 -0.948881269 5.689166546 -0.003340094 0.815935791 0.247838855 0.522315681
1403636662413555456 5.028139114 -0.953669012 5.706493378 -0.006942375 0.815905511 0.249703795 0.521438479
1403636662463555584 5.017751217 -0.960945308 5.726989269 -0.010011586 0.814719617 0.253872782 0.521229506
1403636662513555456 5.014288425 -0.963446021 5.736152172 -0.014270158 0.813265443 0.258341163 0.521205962
1403636662563555584 5.008193493 -0.964348555 5.765452862 -0.013282293 0.812833071 0.262202114 0.519976974
1403636662613555456 4.998935223 -0.967254937 5.780042648 -0.009331478 0.810804188 0.267656684 0.520451248
1403636662663555584 4.998962402 -0.968062639 5.799438000 -0.002001686 0.809497416 0.273067623 0.519753873
1403636662713555456 4.991427422 -0.963806629 5.824951172 0.007215536 0.808757544 0.275919259 0.519353092
1403636662763555584 4.990137100 -0.968341649 5.837873459 0.012238828 0.807828486 0.278375715 0.519394159
1403636662813555456 4.984050274 -0.970361650 5.852355957 0.016735563 0.807175338 0.280626088 0.519073188
1403636662863555584 4.984160423 -0.963700235 5.876311302 0.017609490 0.807049334 0.282231748 0.518368959
1403636662913555456 4.979672909 -0.956697166 5.891352654 0.014948720 0.806526899 0.284260422 0.518157244
1403636662963555584 4.973390579 -0.946640074 5.907463074 0.012747197 0.805728137 0.286578536 0.518181741
1403636663013555456 4.970332623 -0.948148608 5.921730995 0.012408650 0.803959072 0.292425931 0.517670572
1403636663063555584 4.966077805 -0.935519934 5.933485508 0.015594888 0.802304447 0.297003180 0.517545581
1403636663113555456 4.963013649 -0.931650877 5.945749760 0.017705828 0.801085114 0.300649434 0.517261147
1403636663163555584 4.961908340 -0.932178557 5.951852798 0.017212611 0.800025523 0.304609001 0.516600549
1403636663213555456 4.956052303 -0.922184646 5.956913471 0.013211610 0.800993860 0.302389741 0.516521752
1403636663263555584 4.952075481 -0.915383339 5.962708473 0.002898084 0.803385258 0.296807587 0.516206384
1403636663313555456 4.952582836 -0.905456483 5.961608887 -0.006289860 0.804801166 0.292736530 0.516295254
1403636663363555584 4.955070496 -0.901032686 5.968461990 -0.015630674 0.806190968 0.290612251 0.515127540
1403636663413555456 4.951660633 -0.883637547 5.966875076 -0.023847861 0.806158781 0.288830638 0.515864491
1403636663463555584 4.954326153 -0.870717049 5.970719814 -0.029783554 0.806037724 0.289146721 0.515567899
1403636663513555456 4.959944725 -0.855073690 5.972418308 -0.035309456 0.805683136 0.289919078 0.515339553
1403636663563555584 4.966162682 -0.839722872 5.977860451 -0.038865261 0.805672407 0.289885253 0.515119314
1403636663613555456 4.974169254 -0.828537881 5.986618996 -0.040422857 0.805310428 0.291162252 0.514845192
1403636663663555584 4.986049175 -0.807572663 5.989028931 -0.041459959 0.805378020 0.291181803 0.514646053
1403636663713555456 4.995924950 -0.792496800 6.006176949 -0.045395710 0.806818604 0.287199140 0.514295220
1403636663763555584 5.015515327 -0.779807270 5.993684769 -0.048541386 0.806702673 0.284830540 0.515505731
1403636663813555456 5.041519165 -0.769977212 5.991952896 -0.053272475 0.808131814 0.278739780 0.516129076
1403636663863555584 5.065856457 -0.770502925 5.985578537 -0.056482051 0.809052110 0.273659021 0.517063916
1403636663913555456 5.082136631 -0.754310906 5.986070633 -0.056426402 0.810420930 0.266311854 0.518760145
1403636663963555584 5.111748695 -0.753173470 5.997076035 -0.057327043 0.812671006 0.258358747 0.519163013
1403636664013555456 5.135100365 -0.740801215 6.008562565 -0.055575754 0.815195084 0.248288885 0.520308495
1403636664063555584 5.167892456 -0.738991022 6.021151543 -0.052261278 0.816628456 0.244763032 0.520074725
1403636664113555456 5.205224991 -0.747221649 6.023887157 -0.048389785 0.815668046 0.243958160 0.522329926
1403636664163555584 5.237678528 -0.751421034 6.035998344 -0.042144366 0.815699518 0.242631763 0.523438513
1403636664213555456 5.273977757 -0.753893673 6.051268578 -0.033956856 0.815440953 0.241292834 0.525053024
1403636664263555584 5.311022758 -0.759328902 6.070806026 -0.026491303 0.815188885 0.240319088 0.526319265
1403636664313555456 5.347298622 -0.766964853 6.083609104 -0.021533385 0.814320683 0.239858255 0.528096676
1403636664363555584 5.380087852 -0.762973428 6.100927830 -0.017722609 0.813206494 0.239273742 0.530216217
1403636664413555456 5.413789749 -0.760641694 6.125825405 -0.014266429 0.812615573 0.238724038 0.531472683
1403636664463555584 5.451148033 -0.760579646 6.152252674 -0.012972668 0.811720192 0.239504397 0.532521963
1403636664513555456 5.489016056 -0.747202039 6.177587509 -0.008520833 0.811131179 0.237906978 0.534222603
1403636664563555584 5.522197723 -0.740283489 6.200297832 -0.006237518 0.809312940 0.238422289 0.536775947
1403636664613555456 5.553312778 -0.729425430 6.226835728 0.000368038 0.807274997 0.238842636 0.539686263
1403636664663555584 5.589048386 -0.727304459 6.249978542 0.003473461 0.805520058 0.240250453 0.541668832
1403636664713555456 5.621533394 -0.725397706 6.281618595 0.006745788 0.803588688 0.242884129 0.543329597
1403636664763555584 5.647490025 -0.719497323 6.308158398 0.004551295 0.802768350 0.242386431 0.544785321
1403636664813555456 5.672903061 -0.710563064 6.337173939 0.001054654 0.801837265 0.239428729 0.547475815
1403636664863555584 5.709574699 -0.730948210 6.363321781 -0.001111770 0.800533295 0.242664620 0.547959030
1403636664913555456 5.740566254 -0.726261854 6.391079426 -0.000250310 0.799609601 0.241754904 0.549708128
1403636664963555584 5.765997887 -0.730720758 6.414877892 -0.002058665 0.797863066 0.244015843 0.551240921
1403636665013555456 5.810370445 -0.754725695 6.444279671 -0.003904990 0.796107054 0.251139998 0.550569773
1403636665063555584 5.821883678 -0.735908985 6.455869198 -0.003035379 0.792818844 0.251487464 0.555142522
1403636665113555456 5.845701218 -0.737187266 6.509849548 -0.006104420 0.792638779 0.250043154 0.556026042
1403636665163555584 5.880259991 -0.761339664 6.527208328 -0.008310972 0.790600479 0.255251318 0.556532741
1403636665213555456 5.887141228 -0.785829425 6.575860977 -0.005505068 0.790502489 0.255207539 0.556726694
1403636665263555584 5.911926270 -0.820302248 6.595007896 0.002434692 0.789491832 0.259275585 0.556302905
1403636665313555456 5.956223488 -0.868853927 6.619776726 0.005927544 0.789774358 0.263489366 0.553890467
1403636665363555584 5.998950005 -0.863971829 6.634003639 0.008262206 0.789509118 0.261753082 0.555060744
1403636665413555456 6.005953789 -0.821686745 6.662355900 0.009025880 0.790438652 0.248696908 0.559709847
1403636665463555584 6.045703411 -0.853514194 6.689397812 0.004173202 0.792041719 0.250576049 0.556654394
1403636665513555456 6.078733444 -0.885026217 6.708441257 -0.003831559 0.792758226 0.251290798 0.555313051
1403636665563555584 6.105475426 -0.911184788 6.741886139 -0.009633457 0.795079231 0.249007434 0.552947938
1403636665613555456 6.130538940 -0.928380251 6.765965462 -0.014790662 0.795493960 0.248240605 0.552582204
1403636665663555584 6.160886765 -0.943285227 6.763323307 -0.016596176 0.793933928 0.249635950 0.554143846
1403636665713555456 6.187350750 -0.950639367 6.792459488 -0.016681610 0.795748413 0.246418983 0.552977145
1403636665763555584 6.218129158 -0.977921486 6.825755119 -0.016118499 0.798084617 0.243445665 0.550940394
1403636665813555456 6.251276016 -0.983894706 6.843963146 -0.013210993 0.798721671 0.241027817 0.551157653
1403636665863555584 6.271333218 -0.996366501 6.868081093 -0.004285664 0.798640072 0.240737259 0.551544368
1403636665913555456 6.300746918 -1.020884156 6.891866684 0.004117929 0.797749996 0.244857967 0.551019490
1403636665963555584 6.331359863 -1.044119596 6.916130066 0.011210380 0.796651244 0.249807939 0.550288141
1403636666013555456 6.358869076 -1.067077994 6.943316936 0.015837636 0.796127737 0.254808217 0.548637033
1403636666063555584 6.380519867 -1.073468208 6.976796150 0.018915903 0.795810282 0.254362375 0.549206614
1403636666113555456 6.404622078 -1.090761304 7.000734806 0.018144032 0.796170354 0.253830224 0.548957050
1403636666163555584 6.427843094 -1.095773458 7.034418106 0.015245692 0.798216343 0.249140128 0.548222065
1403636666213555456 6.449841499 -1.104943871 7.050627708 0.014074862 0.798296511 0.247054994 0.549079537
1403636666263555584 6.481145859 -1.129285574 7.083136559 0.013504157 0.798727691 0.249151006 0.547517538
1403636666313555456 6.500757217 -1.129441500 7.115264893 0.016357714 0.799414217 0.246832654 0.547487855
1403636666363555584 6.517160416 -1.133738279 7.137939453 0.018960875 0.798321605 0.246577621 0.549110770
1403636666413555456 6.534626007 -1.146136045 7.165008545 0.021125481 0.796612680 0.250292540 0.549832225
1403636666463555584 6.552784920 -1.151537418 7.196796894 0.022406662 0.796006262 0.251889139 0.549930751
1403636666513555456 6.568363190 -1.157560945 7.223352909 0.021825340 0.794941902 0.253128082 0.550924063
1403636666563555584 6.588788986 -1.162399650 7.245854855 0.018252112 0.794342637 0.253712654 0.551649034
1403636666613555456 6.602451801 -1.180120468 7.276854515 0.013182892 0.793802857 0.255604833 0.551696718
1403636666663555584 6.619864464 -1.191963077 7.291652203 0.007332700 0.792999089 0.256208986 0.552680373
1403636666713555456 6.634174824 -1.206115365 7.311585426 0.001419580 0.791719496 0.257597089 0.553915203
1403636666763555584 6.646249771 -1.224912286 7.336127281 -0.003611000 0.790445268 0.260195762 0.554510057
1403636666813555456 6.662954330 -1.236614347 7.351398945 -0.005056122 0.788510978 0.263874978 0.555513144
1403636666863555584 6.669754982 -1.270506263 7.372087955 -0.007002645 0.785764635 0.271801353 0.555561900
1403636666913555456 6.680837631 -1.298092723 7.397757053 -0.003762372 0.781725645 0.282441080 0.555983782
1403636666963555584 6.698173523 -1.272128344 7.408032417 0.003340013 0.777579188 0.288736016 0.558561563
1403636667013555456 6.717528343 -1.279384613 7.430440426 0.006696602 0.776685953 0.291557848 0.558308244
1403636667063555584 6.731242180 -1.292146564 7.443928242 0.009051117 0.776302397 0.291705638 0.558731139
1403636667113555456 6.750235558 -1.295440078 7.467750549 0.009173702 0.780024290 0.281600833 0.558729708
1403636667163555584 6.765452385 -1.291502953 7.505323887 0.007872188 0.786040843 0.265623957 0.558141351
1403636667213555456 6.795262814 -1.317118168 7.507542610 0.005592712 0.787937284 0.260125756 0.558084309
1403636667263555584 6.806023598 -1.311478138 7.541827679 0.002564894 0.792219639 0.247671261 0.557709932
1403636667313555456 6.828222275 -1.317244887 7.554492474 0.000572741 0.793543458 0.243237585 0.557784796
1403636667363555584 6.842891693 -1.319604039 7.571661472 0.000239965 0.794218302 0.240441799 0.558036685
1403636667413555456 6.865957260 -1.320460320 7.589993000 -0.000930838 0.794268072 0.240652382 0.557874322
1403636667463555584 6.885758400 -1.321690798 7.600903511 -0.004860361 0.792558908 0.242462456 0.559498549
1403636667513555456 6.892263412 -1.312954903 7.612133026 -0.006649017 0.790579140 0.245105147 0.561127365
1403636667563555584 6.907839775 -1.316214561 7.639328957 -0.005749611 0.788827956 0.253968984 0.559658051
1403636667613555456 6.922917843 -1.310653210 7.651305199 -0.005217625 0.786221206 0.259836197 0.560637236
1403636667663555584 6.927462578 -1.312206864 7.657507896 -0.003090828 0.783103049 0.265591681 0.562317550
1403636667713555456 6.918401718 -1.325649500 7.675595284 -0.000750739 0.781686366 0.268411428 0.562957466
1403636667763555584 6.970007420 -1.327800155 7.697235584 0.000253085 0.781734228 0.269861400 0.562197745
1403636667813555456 6.993750572 -1.332528353 7.705916882 0.001923318 0.781601310 0.270220488 0.562206924
1403636667863555584 7.013020515 -1.340237379 7.719238281 0.003628829 0.781831264 0.271181941 0.561415136
1403636667913555456 7.019248009 -1.349107027 7.734769821 0.004673751 0.781870246 0.270567358 0.561649740
1403636667963555584 7.025544643 -1.353119135 7.737032413 0.004069078 0.781361580 0.271219313 0.562047601
1403636668013555456 7.044990540 -1.354366660 7.731075764 0.005278928 0.780592263 0.272314876 0.562576652
1403636668063555584 7.072769165 -1.358116508 7.770509720 0.002681832 0.783224285 0.269044638 0.560506523
1403636668113555456 7.098018646 -1.355845571 7.782443047 0.000571740 0.784275711 0.267534256 0.559764862
1403636668163555584 7.118284225 -1.358377218 7.798287392 -0.002680406 0.785988271 0.265337646 0.558400452
1403636668213555456 7.140185356 -1.357535362 7.816805363 -0.006580178 0.786947191 0.264924526 0.557212532
1403636668263555584 7.152952671 -1.349371433 7.825963974 -0.008919511 0.787505269 0.264701664 0.556496978
1403636668313555456 7.179498196 -1.339342117 7.837158203 -0.010425649 0.788424194 0.264623225 0.555205584
1403636668363555584 7.201054573 -1.336610556 7.858158588 -0.011132255 0.789493501 0.264603853 0.553679526
1403636668413555456 7.217255592 -1.332993984 7.871211052 -0.010759264 0.790418148 0.263355434 0.552962303
1403636668463555584 7.233754158 -1.322415352 7.879594803 -0.009409885 0.791494489 0.261919379 0.552128792
1403636668513555456 7.263474464 -1.321190953 7.900258541 -0.009837055 0.792547226 0.261123568 0.550986946
1403636668563555584 7.286560059 -1.316951394 7.916086197 -0.009862801 0.793188870 0.261508495 0.549879491
1403636668613555456 7.304868698 -1.307989955 7.933476448 -0.009809686 0.793872118 0.260855287 0.549204350
1403636668663555584 7.332767487 -1.298568726 7.950290203 -0.010367502 0.794558346 0.260750502 0.548250556
1403636668713555456 7.362789154 -1.292355418 7.969477654 -0.013565051 0.796036243 0.258510947 0.547096312
1403636668763555584 7.384869576 -1.286076427 7.986198902 -0.017139772 0.797859311 0.253628135 0.546625614
1403636668813555456 7.410219193 -1.278625250 8.003113747 -0.018971572 0.799887240 0.248787925 0.545825064
1403636668863555584 7.436862469 -1.276326895 8.017573357 -0.022837967 0.801416159 0.243676111 0.545740306
1403636668913555456 7.463852406 -1.272602201 8.036894798 -0.024116838 0.803610325 0.237373695 0.545236170
1403636668963555584 7.492824078 -1.273855686 8.061759949 -0.020973317 0.804346979 0.235612080 0.545044005
1403636669013555456 7.517461777 -1.280450702 8.085881233 -0.015444151 0.804041564 0.236654416 0.545227706
1403636669063555584 7.548264503 -1.286600232 8.105188370 -0.009302542 0.803727090 0.237853944 0.545308769
1403636669113555456 7.572595596 -1.292749643 8.129976273 -0.003492031 0.803367078 0.239422336 0.545221150
1403636669163555584 7.600412846 -1.304176569 8.151439667 -0.000718740 0.803128481 0.240790665 0.544980586
1403636669213555456 7.626497269 -1.309994340 8.176423073 0.001563302 0.803386927 0.240424275 0.544759691
1403636669263555584 7.649705887 -1.318232536 8.202738762 0.002309474 0.803603232 0.240260974 0.544509947
1403636669313555456 7.675340652 -1.323601365 8.228528976 0.001537444 0.803824008 0.240043432 0.544282794
1403636669363555584 7.700615883 -1.334112287 8.261470795 0.001280415 0.803868949 0.241477415 0.543582201
1403636669413555456 7.720372200 -1.334965110 8.291839600 0.002917110 0.804205835 0.240429059 0.543542325
1403636669463555584 7.738229752 -1.336946487 8.319227219 0.005726959 0.804419637 0.238801509 0.543920994
1403636669513555456 7.764165878 -1.339091301 8.352941513 0.007015047 0.804928720 0.236267194 0.544259429
1403636669563555584 7.784440994 -1.341711521 8.383245468 0.009008486 0.805739522 0.233289868 0.544314623
1403636669613555456 7.802548885 -1.346354008 8.414456367 0.011500543 0.806901991 0.228592992 0.544538498
1403636669663555584 7.821129799 -1.346629381 8.446765900 0.014387920 0.807645380 0.224005222 0.545273900
1403636669713555456 7.839088440 -1.351175427 8.477913857 0.017404154 0.808486402 0.219911486 0.545605958
1403636669763555584 7.853398323 -1.360949516 8.513906479 0.019679394 0.808633327 0.218457386 0.545894921
1403636669813555456 7.870459557 -1.370774150 8.547209740 0.028125051 0.806115210 0.223610312 0.547161400
1403636669863555584 7.876729012 -1.380710721 8.586523056 0.040364176 0.802425921 0.232113153 0.548276246
1403636669913555456 7.886334419 -1.389546275 8.624317169 0.049709219 0.797657371 0.243746996 0.549417078
1403636669963555584 7.887827873 -1.405658603 8.654282570 0.056006473 0.793549478 0.253832668 0.550192118
1403636670013555456 7.891213417 -1.418824911 8.695274353 0.057938036 0.791269958 0.260557324 0.550131619
1403636670063555584 7.887789726 -1.437616706 8.718859673 0.059737481 0.788401186 0.266698807 0.551114142
1403636670113555456 7.886660576 -1.452714086 8.750275612 0.061782107 0.785908878 0.270983696 0.552356839
1403636670163555584 7.883104324 -1.467236519 8.777954102 0.066658527 0.784125388 0.271558136 0.554039836
1403636670213555456 7.880121231 -1.493634462 8.792365074 0.075047649 0.780716836 0.273377240 0.556878805
1403636670263555584 7.872148514 -1.502259612 8.819920540 0.084851943 0.778608024 0.272557199 0.558822095
1403636670313555456 7.854686737 -1.510158539 8.834125519 0.092546500 0.775552690 0.272694021 0.561774969
1403636670363555584 7.844825745 -1.517713189 8.854673386 0.096767239 0.772378683 0.274191678 0.564700186
1403636670413555456 7.826788902 -1.524264812 8.870272636 0.098831117 0.768533647 0.276198924 0.568596959
1403636670463555584 7.806062698 -1.528682113 8.878421783 0.100828618 0.763039589 0.278971523 0.574263990
1403636670513555456 7.786500931 -1.535262346 8.883744240 0.102205671 0.757635534 0.280569106 0.580364883
1403636670563555584 7.767385483 -1.543831229 8.888494492 0.102100693 0.751938462 0.281430990 0.587333560
1403636670613555456 7.728950500 -1.539954782 8.879109383 0.102989323 0.745013356 0.280701041 0.596284449
1403636670663555584 7.704156876 -1.550591469 8.880379677 0.100821190 0.739421070 0.278945118 0.604384959
1403636670713555456 7.662990093 -1.558030367 8.859666824 0.099809520 0.732539833 0.276622832 0.613924444
1403636670763555584 7.628519535 -1.562070131 8.849843979 0.099508941 0.726143777 0.273901999 0.622728586
1403636670813555456 7.595517159 -1.575009942 8.823338509 0.100169450 0.717384815 0.273625344 0.632814586
1403636670863555584 7.551117897 -1.568065643 8.794543266 0.104262747 0.707677245 0.272790492 0.643356442
1403636670913555456 7.508132935 -1.574171662 8.758802414 0.108012296 0.697266877 0.272391528 0.654182792
1403636670963555584 7.456411362 -1.572951317 8.741601944 0.114994168 0.687027752 0.270673871 0.664458275
1403636671013555456 7.407790661 -1.569321990 8.691184044 0.118262924 0.675049484 0.267047584 0.677501082
1403636671063555584 7.356086731 -1.556913853 8.646077156 0.118722931 0.665035546 0.260093600 0.689915836
1403636671113555456 7.309405804 -1.561914444 8.589310646 0.114678986 0.654859602 0.254180312 0.702424347
1403636671163555584 7.265514374 -1.556342721 8.536566734 0.108445875 0.645847976 0.247705013 0.713976204
1403636671213555456 7.205417633 -1.554183006 8.479853630 0.100519776 0.637541771 0.241549730 0.724630892
1403636671263555584 7.132333755 -1.555318356 8.411432266 0.091354236 0.630153418 0.236840457 0.733803511
1403636671313555456 7.068848133 -1.564950705 8.350270271 0.073510468 0.625453055 0.230404466 0.741834521
1403636671363555584 7.014303207 -1.545244694 8.266847610 0.053661019 0.622332394 0.221024424 0.748980045
1403636671413555456 6.956405163 -1.549069405 8.187145233 0.032389849 0.618505955 0.211839795 0.755992830
1403636671463555584 6.894906998 -1.543415070 8.113531113 0.014190231 0.613275766 0.205289021 0.762592852
1403636671513555456 6.838022709 -1.530166984 8.043901443 -0.000786578 0.607113123 0.201180503 0.768725872
1403636671563555584 6.770399094 -1.513285398 7.951291084 -0.011032654 0.599163651 0.201021954 0.774900854
1403636671613555456 6.710206985 -1.507296324 7.876077175 -0.021884330 0.593134880 0.202251837 0.778977692
1403636671663555584 6.653922081 -1.495558262 7.802845955 -0.030484792 0.587871194 0.203879729 0.782247543
1403636671713555456 6.603355885 -1.515195131 7.743562698 -0.039279152 0.584529400 0.207471639 0.783414364
1403636671763555584 6.534059525 -1.488270998 7.662004471 -0.040976338 0.581038892 0.209434122 0.785399377
1403636671813555456 6.497330666 -1.487098932 7.554848671 -0.049325313 0.576471806 0.210753232 0.787927866
1403636671863555584 6.443270683 -1.454253674 7.506621361 -0.052497838 0.576147258 0.211475164 0.787766814
1403636671913555456 6.398102760 -1.441648245 7.427495003 -0.057766378 0.574362993 0.215839699 0.787517250
1403636671963555584 6.353384495 -1.438793659 7.363931656 -0.066377819 0.574298859 0.217085749 0.786542177
1403636672013555456 6.320822716 -1.426901817 7.282958984 -0.073743179 0.573131204 0.218609050 0.786315918
1403636672063555584 6.287803650 -1.402933836 7.246279716 -0.079057679 0.576909423 0.214520261 0.784159720
1403636672113555456 6.267209053 -1.400103569 7.181046963 -0.083968617 0.579382598 0.207597792 0.783688903
1403636672163555584 6.245722294 -1.411617279 7.117623329 -0.088086858 0.581945717 0.201848209 0.782839119
1403636672213555456 6.209538460 -1.405134916 7.066278934 -0.090256594 0.585545123 0.196048930 0.781380534
1403636672263555584 6.211273670 -1.419873714 7.005881786 -0.091532968 0.587287784 0.193923131 0.780454099
1403636672313555456 6.191199780 -1.428140402 6.949193001 -0.091698818 0.589161396 0.189446658 0.780121863
1403636672363555584 6.189244270 -1.447222948 6.903415203 -0.092624225 0.592455924 0.182293549 0.779221296
1403636672413555456 6.182307243 -1.452250719 6.848489285 -0.090530753 0.595418632 0.174155295 0.779070437
1403636672463555584 6.169717789 -1.422459126 6.828797817 -0.083713844 0.600459993 0.159773260 0.779045761
1403636672513555456 6.180315971 -1.418032885 6.780739784 -0.067941271 0.601127207 0.156935453 0.780641675
1403636672563555584 6.144595623 -1.433074832 6.771863461 -0.053642664 0.604578972 0.151906207 0.780084133
1403636672613555456 6.144110680 -1.411048174 6.744775772 -0.037367757 0.604560792 0.151607990 0.781104922
1403636672663555584 6.158496380 -1.406974673 6.715920448 -0.024268726 0.603819489 0.154280812 0.781671584
1403636672713555456 6.167267323 -1.383330941 6.696090698 -0.016936775 0.602455795 0.158857942 0.782000184
1403636672763555584 6.139826775 -1.356390119 6.689658165 -0.016783025 0.601150036 0.163249359 0.782104015
1403636672813555456 6.144213676 -1.344561219 6.672941685 -0.019293925 0.597371817 0.171285436 0.783221543
1403636672863555584 6.143929482 -1.339729309 6.638812065 -0.021384906 0.591925800 0.174446866 0.786596954
1403636672913555456 6.143725395 -1.317755699 6.628562450 -0.022582237 0.587096751 0.171895266 0.790733516
1403636672963555584 6.148684025 -1.306403399 6.611309528 -0.023501538 0.581088841 0.171376541 0.795244336
1403636673013555456 6.130552292 -1.295845032 6.613655090 -0.025064960 0.576405585 0.168700576 0.799167335
1403636673063555584 6.140811920 -1.286562920 6.594576359 -0.028560067 0.569821000 0.164408669 0.804647803
1403636673113555456 6.143560410 -1.273249865 6.578640938 -0.030778358 0.562469304 0.162400454 0.810127795
1403636673163555584 6.137347698 -1.277159333 6.576745033 -0.036960624 0.556446433 0.164345384 0.813628852
1403636673213555456 6.135723114 -1.262710810 6.559864044 -0.044112846 0.549060643 0.165602922 0.818023324
1403636673263555584 6.134925842 -1.276903152 6.558701515 -0.052373230 0.544161797 0.168790415 0.820155323
1403636673313555456 6.132897854 -1.273507357 6.555906773 -0.058101051 0.539506555 0.170402914 0.822508216
1403636673363555584 6.132737637 -1.278942823 6.554922581 -0.062376939 0.536023736 0.170892105 0.824368536
1403636673413555456 6.152889252 -1.289731503 6.546674728 -0.062509477 0.532993197 0.173054680 0.825870991
1403636673463555584 6.159550190 -1.301821709 6.529044151 -0.062379397 0.529791653 0.173125774 0.827923357
1403636673513555456 6.172075272 -1.298055649 6.546928406 -0.061604727 0.529529333 0.171349034 0.828518569
1403636673563555584 6.190741539 -1.298991203 6.554288864 -0.058497112 0.528489292 0.168785036 0.829932988
1403636673613555456 6.200764179 -1.299298286 6.563004494 -0.053247765 0.529369891 0.162748933 0.830930173
1403636673663555584 6.198436260 -1.301257610 6.571568966 -0.046928208 0.530365288 0.157476082 0.831692040
1403636673713555456 6.222978115 -1.298680067 6.591247559 -0.040275622 0.531148553 0.152179122 0.832526624
1403636673763555584 6.235769749 -1.292569995 6.602694511 -0.032641064 0.532014430 0.146293491 0.833362699
1403636673813555456 6.257572174 -1.301592350 6.612741470 -0.026805114 0.531598926 0.144108310 0.834216297
1403636673863555584 6.269630432 -1.298197031 6.632276535 -0.024420463 0.532619119 0.140110955 0.834319770
1403636673913555456 6.289425373 -1.318020463 6.650252342 -0.026688507 0.532787859 0.139441475 0.834254682
1403636673963555584 6.310924530 -1.322813630 6.664428711 -0.026890676 0.532283664 0.139105514 0.834626019
1403636674013555456 6.324705601 -1.322771549 6.680025101 -0.026562521 0.531790555 0.140552849 0.834708393
1403636674063555584 6.345242500 -1.343520641 6.698267937 -0.026961669 0.531111121 0.143205598 0.834677279
1403636674113555456 6.345103741 -1.352458715 6.742029190 -0.026975172 0.532306433 0.142439276 0.834046304
1403636674163555584 6.362403393 -1.340757847 6.751452446 -0.023946999 0.531015575 0.143254086 0.834821701
1403636674213555456 6.393887043 -1.349415779 6.773044586 -0.021723414 0.530350685 0.143598080 0.835245967
1403636674263555584 6.403329372 -1.354435086 6.802979469 -0.017118799 0.529901087 0.146588013 0.835119009
1403636674313555456 6.407083035 -1.351203322 6.829221725 -0.011493267 0.528881371 0.151003122 0.835075080
1403636674363555584 6.435249329 -1.370669127 6.858861446 -0.008787638 0.525770843 0.158390507 0.835703433
1403636674413555456 6.429866314 -1.349873543 6.884125710 -0.002468906 0.521763980 0.162438020 0.837478459
1403636674463555584 6.447300911 -1.361841917 6.910808086 0.000282369 0.516264021 0.165832415 0.840220809
1403636674513555456 6.467663765 -1.349061728 6.943977833 0.004499609 0.510299087 0.166919425 0.843630552
1403636674563555584 6.457478523 -1.343066573 6.986180305 0.006085952 0.506527364 0.165895820 0.846091926
1403636674613555456 6.463511467 -1.326638103 7.006692886 0.007335036 0.501904547 0.163054407 0.849382877
1403636674663555584 6.500442028 -1.311758041 7.031492710 0.007536886 0.497505188 0.160467997 0.852456331
1403636674713555456 6.520148277 -1.318021059 7.044955730 0.006140081 0.492083460 0.161224514 0.855466425
1403636674763555584 6.525491238 -1.322082996 7.078239918 0.000710893 0.488662124 0.163619831 0.856993198
1403636674813555456 6.545966148 -1.287433386 7.095923424 -0.003596308 0.483698308 0.167678595 0.859015107
1403636674863555584 6.555525780 -1.286478162 7.125432014 -0.011870267 0.479959011 0.171315461 0.860319376
1403636674913555456 6.572579861 -1.264919758 7.160827637 -0.017724708 0.477725178 0.173157930 0.861092806
1403636674963555584 6.576357365 -1.259699106 7.190537453 -0.023469213 0.475742936 0.176187620 0.861438215
1403636675013555456 6.607675552 -1.250189066 7.205116272 -0.028228316 0.472626597 0.178123415 0.862611890
1403636675063555584 6.633059502 -1.255564451 7.221202374 -0.033697199 0.471190423 0.180781037 0.862648427
1403636675113555456 6.653900623 -1.259616375 7.255560875 -0.038611129 0.472717822 0.177974090 0.862190425
1403636675163555584 6.676143646 -1.257708311 7.270748615 -0.044265125 0.474269241 0.173151061 0.862048745
1403636675213555456 6.705934525 -1.272380590 7.284388065 -0.049492072 0.475606531 0.165394902 0.862550557
1403636675263555584 6.741875648 -1.258955479 7.310001373 -0.050996073 0.478669167 0.157836065 0.862185001
1403636675313555456 6.757632256 -1.260097504 7.345235825 -0.052580636 0.481573403 0.151273355 0.861648858
1403636675363555584 6.788263798 -1.276138306 7.363468647 -0.050061565 0.482965052 0.144539043 0.862175763
1403636675413555456 6.826862335 -1.292382121 7.396759987 -0.044387445 0.483527243 0.137745649 0.863282859
1403636675463555584 6.857332230 -1.296423674 7.424352646 -0.036951348 0.482178390 0.131948546 0.865290761
1403636675513555456 6.889003277 -1.308447123 7.452065468 -0.032627471 0.479564309 0.124453418 0.868023515
1403636675563555584 6.924645901 -1.320935726 7.490962505 -0.028688636 0.477800667 0.117311321 0.870127320
1403636675613555456 6.954239368 -1.330406785 7.521293640 -0.025067538 0.474768758 0.110321842 0.872808874
1403636675663555584 6.983548641 -1.337135792 7.566210747 -0.022520076 0.471601814 0.105891764 0.875140846
1403636675713555456 7.010787010 -1.343306780 7.598325729 -0.017754709 0.466046333 0.102407791 0.878634274
1403636675763555584 7.039688587 -1.349991560 7.637574196 -0.011554058 0.459313303 0.100351512 0.882511973
1403636675813555456 7.055605888 -1.348905444 7.669040203 -0.003078097 0.450078636 0.104199953 0.886883378
1403636675863555584 7.078634739 -1.360879898 7.715695381 0.004714829 0.439657658 0.110291451 0.891355574
1403636675913555456 7.112845898 -1.361994743 7.759026051 0.009402839 0.426574022 0.117706560 0.896711409
1403636675963555584 7.137169361 -1.366687298 7.796994209 0.011956998 0.413766533 0.125554159 0.901604354
1403636676013555456 7.159782410 -1.377523661 7.833911419 0.010692935 0.401862532 0.129699126 0.906405151
1403636676063555584 7.176640987 -1.365703464 7.887746811 0.008826957 0.392265469 0.127614573 0.910914063
1403636676113555456 7.201948643 -1.371096611 7.919705391 0.003370330 0.383314431 0.123193204 0.915359020
1403636676163555584 7.220540047 -1.368597031 7.954999924 -0.002673430 0.375694633 0.112654001 0.919867098
1403636676213555456 7.252235413 -1.360267282 7.996717930 -0.007991956 0.367936403 0.102047406 0.924199820
1403636676263555584 7.270307541 -1.352833748 8.029366493 -0.014584291 0.360192180 0.088088773 0.928595304
1403636676313555456 7.281189442 -1.349745989 8.074790001 -0.021055777 0.352213860 0.077779062 0.932444334
1403636676363555584 7.324231148 -1.353504896 8.109451294 -0.024936270 0.341907829 0.066575982 0.937040448
1403636676413555456 7.336730480 -1.340630531 8.149763107 -0.027742665 0.333001643 0.055701301 0.940870643
1403636676463555584 7.353383541 -1.342400789 8.189892769 -0.029849356 0.321936101 0.050055791 0.944965899
1403636676513555456 7.382615566 -1.353612423 8.226511955 -0.031311300 0.309281766 0.048658345 0.949208498
1403636676563555584 7.399116039 -1.365793943 8.264595032 -0.029384166 0.296969742 0.050239652 0.953111529
1403636676613555456 7.401501179 -1.372424364 8.311797142 -0.026832404 0.286945224 0.051895604 0.956163824
1403636676663555584 7.414444447 -1.379878283 8.355800629 -0.023225201 0.277764440 0.054268122 0.958833933
1403636676713555456 7.434920311 -1.393297195 8.395954132 -0.020598534 0.269158304 0.057135012 0.961179018
1403636676763555584 7.449172974 -1.403612137 8.436308861 -0.016488990 0.262682378 0.060395490 0.962849140
1403636676813555456 7.460049629 -1.424794674 8.478387833 -0.015339024 0.256724477 0.063097097 0.964300811
1403636676863555584 7.471637726 -1.439837933 8.520484924 -0.014183056 0.250423044 0.066821821 0.965723515
1403636676913555456 7.482936382 -1.452168226 8.558155060 -0.011672640 0.246411175 0.068505652 0.966670692
1403636676963555584 7.495224953 -1.473577261 8.602490425 -0.011234221 0.243349835 0.069334030 0.967392027
1403636677013555456 7.515334129 -1.487817526 8.642293930 -0.011324009 0.241778627 0.067141585 0.967939496
1403636677063555584 7.529653549 -1.490648985 8.676119804 -0.011475116 0.242266372 0.062227435 0.968144119
1403636677113555456 7.540368080 -1.497372270 8.723657608 -0.012307917 0.243937388 0.056796115 0.968048155
1403636677163555584 7.552878857 -1.497168064 8.771780014 -0.013475280 0.245772853 0.052014530 0.967837036
1403636677213555456 7.569367409 -1.494876623 8.818578720 -0.012062536 0.247100994 0.048390545 0.967705488
1403636677263555584 7.582938671 -1.497089028 8.863342285 -0.009911466 0.247519568 0.044151127 0.967825651
1403636677313555456 7.595919609 -1.492690802 8.907434464 -0.005516039 0.245917931 0.041869286 0.968370199
1403636677363555584 7.609784126 -1.500301361 8.945210457 -0.000929177 0.242590144 0.037619997 0.969398737
1403636677413555456 7.623198986 -1.506701589 8.982769012 0.005205647 0.237999260 0.033738382 0.970665216
1403636677463555584 7.626533508 -1.516166806 9.029137611 0.011435403 0.232914791 0.030957460 0.971937001
1403636677513555456 7.634411812 -1.516330957 9.074515343 0.017793359 0.225676388 0.029801119 0.973583817
1403636677563555584 7.636759758 -1.537478685 9.111428261 0.020364946 0.218009368 0.028993864 0.975303292
1403636677613555456 7.636211872 -1.542874336 9.147339821 0.022574741 0.208450750 0.029420137 0.977329552
1403636677663555584 7.635900497 -1.555763483 9.174434662 0.022057151 0.198666006 0.030440547 0.979346037
1403636677713555456 7.636271954 -1.567739248 9.212552071 0.021608189 0.187498420 0.032039348 0.981504440
1403636677763555584 7.635386467 -1.578802943 9.234563828 0.018763645 0.175480396 0.032953501 0.983752310
1403636677813555456 7.628282547 -1.587965250 9.265102386 0.013864239 0.162478417 0.035634108 0.985970974
1403636677863555584 7.629526615 -1.604094744 9.285068512 0.008219807 0.147361785 0.040318239 0.988226414
1403636677913555456 7.629859924 -1.615250826 9.310052872 0.002478257 0.132445574 0.042502910 0.990275502
1403636677963555584 7.628725052 -1.627453089 9.329130173 -0.001464524 0.118475907 0.042993240 0.992024660
1403636678013555456 7.630137444 -1.640639544 9.353802681 -0.005852838 0.105827823 0.039453346 0.993584216
1403636678063555584 7.637994289 -1.649271488 9.369477272 -0.006641482 0.093703255 0.035251811 0.994953692
1403636678113555456 7.638032913 -1.664363742 9.390189171 -0.007760453 0.086087875 0.026940497 0.995893002
1403636678163555584 7.643330574 -1.668849468 9.412388802 -0.006977485 0.079010554 0.018385064 0.996679842
1403636678213555456 7.648546219 -1.675233364 9.436500549 -0.008311936 0.073933423 0.009488716 0.997183383
1403636678263555584 7.653569698 -1.680528879 9.456266403 -0.008294771 0.068217218 0.002339543 0.997633278
1403636678313555456 7.659037113 -1.689336777 9.480309486 -0.008395078 0.061576061 -0.003447716 0.998061121
1403636678363555584 7.666387081 -1.695706725 9.492953300 -0.007528270 0.052476440 -0.004962598 0.998581469
1403636678413555456 7.675371170 -1.704699993 9.511019707 -0.008854837 0.043684565 -0.006897280 0.998982310
1403636678463555584 7.679256916 -1.716548204 9.531075478 -0.009829387 0.035302714 -0.010384802 0.999274313
1403636678513555456 7.678710461 -1.726927280 9.548897743 -0.011110473 0.027448870 -0.014385692 0.999457955
1403636678563555584 7.689039707 -1.737464190 9.564870834 -0.010454740 0.017297609 -0.016767006 0.999655128
1403636678613555456 7.695888996 -1.754916906 9.576672554 -0.010354496 0.006257505 -0.020658992 0.999713361
1403636678663555584 7.696743488 -1.768443704 9.595681190 -0.009979596 -0.003406438 -0.028441880 0.999539793
1403636678713555456 7.707121372 -1.781598926 9.604994774 -0.009336774 -0.013856645 -0.038233902 0.999129117
1403636678763555584 7.709965706 -1.792299390 9.624985695 -0.009117842 -0.023874696 -0.050406445 0.998401761
1403636678813555456 7.715749741 -1.803374887 9.639495850 -0.009357770 -0.033685602 -0.063509874 0.997368634
1403636678863555584 7.718628407 -1.810573459 9.652852058 -0.009740392 -0.042553701 -0.074504785 0.996264696
1403636678913555456 7.716925621 -1.813571453 9.677109718 -0.009249329 -0.050085999 -0.086112879 0.994982600
1403636678963555584 7.718388557 -1.820285678 9.691546440 -0.010062596 -0.059306882 -0.092925787 0.993854225
1403636679013555456 7.715607643 -1.820610046 9.709135056 -0.008528750 -0.069199920 -0.097502969 0.992789924
1403636679063555584 7.711317062 -1.824962854 9.721266747 -0.007682232 -0.080517940 -0.098615155 0.991833091
1403636679113555456 7.707024574 -1.825249434 9.738474846 -0.005392316 -0.092750922 -0.098741688 0.990766525
1403636679163555584 7.697417259 -1.824652076 9.748765945 -0.003386926 -0.105413675 -0.095318414 0.989843845
1403636679213555456 7.686798573 -1.823854566 9.768127441 -0.000359903 -0.120468266 -0.090464890 0.988586545
1403636679263555584 7.678352356 -1.823775172 9.780288696 0.002186978 -0.135672033 -0.085643128 0.987042844
1403636679313555456 7.667207718 -1.826980352 9.788299561 0.002736551 -0.150186390 -0.082870945 0.985174596
1403636679363555584 7.655500889 -1.824537635 9.800012589 0.004540951 -0.164180607 -0.082322881 0.982978642
1403636679413555456 7.641702652 -1.828865290 9.807314873 0.003594777 -0.177135319 -0.084358439 0.980557859
1403636679463555584 7.631881237 -1.833745480 9.814382553 0.003308844 -0.190021336 -0.086220302 0.977981091
1403636679513555456 7.626142979 -1.837267756 9.821691513 0.002696605 -0.202194124 -0.088974394 0.975291669
1403636679563555584 7.620146751 -1.843649626 9.826726913 0.001243345 -0.212375566 -0.091799311 0.972865880
1403636679613555456 7.608191013 -1.851700306 9.826990128 -0.000395951 -0.220589310 -0.093781888 0.970847607
1403636679663555584 7.603467941 -1.860302925 9.833076477 -0.003128218 -0.228107199 -0.096013442 0.968885303
1403636679713555456 7.596119881 -1.870998502 9.836517334 -0.004804574 -0.233416617 -0.099461533 0.967264712
1403636679763555584 7.591323853 -1.885571241 9.833570480 -0.005077417 -0.237349838 -0.102820054 0.965954125
1403636679813555456 7.585516930 -1.898255110 9.834169388 -0.001220683 -0.240552172 -0.104425438 0.965001822
1403636679863555584 7.581492901 -1.916070223 9.835611343 0.002804513 -0.242707416 -0.106873319 0.964190543
1403636679913555456 7.576640129 -1.931917310 9.832322121 0.009135232 -0.243250355 -0.110168107 0.963643491
1403636679963555584 7.572625637 -1.950716138 9.830809593 0.010891923 -0.243057162 -0.114079252 0.963218808
1403636680013555456 7.568585396 -1.965046287 9.825506210 0.014311562 -0.240939766 -0.121219181 0.962833881
1403636680063555584 7.567229271 -1.983976960 9.817806244 0.016784947 -0.238359913 -0.128283873 0.962520659
1403636680113555456 7.561637878 -2.001074076 9.809556961 0.020642772 -0.235006765 -0.137080148 0.962057590
1403636680163555584 7.554582119 -2.018767595 9.801408768 0.021436822 -0.232670665 -0.141286790 0.961999416
1403636680213555456 7.549333096 -2.032945871 9.789318085 0.021891205 -0.232744470 -0.140127361 0.962140918
1403636680263555584 7.539433956 -2.045396805 9.780486107 0.024910316 -0.232249573 -0.138384372 0.962439239
1403636680313555456 7.529459953 -2.056826591 9.764229774 0.026404001 -0.229700416 -0.141306669 0.962586582
1403636680363555584 7.517886162 -2.068237305 9.748136520 0.024815395 -0.225963414 -0.147176802 0.962633729
1403636680413555456 7.509745121 -2.072051764 9.732234001 0.022924678 -0.223085895 -0.152286470 0.962557018
1403636680463555584 7.494587898 -2.073356390 9.714677811 0.020857984 -0.220021591 -0.155785546 0.962749362
1403636680513555456 7.482726097 -2.074956894 9.696790695 0.018789891 -0.218056396 -0.157877013 0.962898314
1403636680563555584 7.467135906 -2.081117630 9.675016403 0.015552304 -0.217235878 -0.156129658 0.963426292
1403636680613555456 7.446795464 -2.078087807 9.652311325 0.014797184 -0.217219651 -0.152434453 0.964033425
1403636680663555584 7.423848152 -2.070546627 9.628533363 0.014396857 -0.216382518 -0.150263891 0.964568377
1403636680713555456 7.405449867 -2.067357779 9.604339600 0.011521064 -0.217012748 -0.146144971 0.965098143
1403636680763555584 7.377574921 -2.064088821 9.576133728 0.006609605 -0.218469590 -0.137344316 0.966107607
1403636680813555456 7.353173256 -2.058961630 9.550170898 0.002589167 -0.221208856 -0.127803460 0.966812372
1403636680863555584 7.329937458 -2.051777363 9.519699097 -0.002567496 -0.224631861 -0.116680592 0.967429399
1403636680913555456 7.298042774 -2.035324097 9.500788689 -0.008639136 -0.227314115 -0.106466718 0.967945516
1403636680963555584 7.270051956 -2.025904655 9.469686508 -0.018068176 -0.228292048 -0.100812361 0.968190610
1403636681013555456 7.245745659 -2.014767885 9.442260742 -0.026740575 -0.228102431 -0.099641763 0.968155861
1403636681063555584 7.215581894 -1.997608423 9.421480179 -0.034740109 -0.226989299 -0.100755192 0.968048215
1403636681113555456 7.199471951 -1.987371445 9.391972542 -0.040373255 -0.226811826 -0.103608906 0.967569947
1403636681163555584 7.170560837 -1.972554445 9.374282837 -0.040138457 -0.225853667 -0.106226720 0.967519939
1403636681213555456 7.149983406 -1.961142778 9.354193687 -0.033779055 -0.225296244 -0.109467670 0.967531562
1403636681263555584 7.119657516 -1.946486592 9.334306717 -0.024470964 -0.224105224 -0.112944350 0.967688799
1403636681313555456 7.091654778 -1.934348345 9.318976402 -0.016802857 -0.225085795 -0.113683276 0.967538178
1403636681363555584 7.062004566 -1.922314405 9.301494598 -0.009640575 -0.225716799 -0.113365136 0.967526376
1403636681413555456 7.038883209 -1.918421388 9.279315948 -0.005403143 -0.227444798 -0.111274049 0.967397392
1403636681463555584 7.006561279 -1.911508083 9.262528419 -0.002619968 -0.228585348 -0.108816467 0.967419684
1403636681513555456 6.978384972 -1.908635616 9.240246773 -0.001457754 -0.229837462 -0.106690720 0.967362225
1403636681563555584 6.952690601 -1.904769182 9.218824387 -0.001044611 -0.231024399 -0.106850520 0.967062354
1403636681613555456 6.923546791 -1.896310806 9.196729660 -0.000038328 -0.230913907 -0.109830171 0.966755450
1403636681663555584 6.895151138 -1.891672254 9.175426483 0.000348429 -0.231615558 -0.111642957 0.966379821
1403636681713555456 6.867467880 -1.882581234 9.155626297 0.000965060 -0.231900305 -0.112681560 0.966190517
1403636681763555584 6.840126991 -1.878566980 9.124447823 0.001204489 -0.231972218 -0.113882169 0.966032267
1403636681813555456 6.813137054 -1.869351268 9.100581169 0.001941959 -0.232814267 -0.114356481 0.965772390
1403636681863555584 6.784406662 -1.862808585 9.077547073 0.001948388 -0.233682916 -0.114170544 0.965584576
1403636681913555456 6.758557320 -1.855995774 9.054115295 0.002565826 -0.235222623 -0.113246918 0.965318024
1403636681963555584 6.731095314 -1.850432873 9.025998116 0.002172781 -0.236513913 -0.112531856 0.965087056
1403636682013555456 6.697619438 -1.842245221 9.005699158 0.002342748 -0.237320989 -0.111672394 0.964988351
1403636682063555584 6.668923378 -1.843816996 8.962770462 0.000787199 -0.238707229 -0.109341323 0.964915872
1403636682113555456 6.639130592 -1.839177966 8.942725182 0.001084230 -0.239566281 -0.108810790 0.964762688
1403636682163555584 6.611606121 -1.839658141 8.907455444 0.000095063 -0.240619346 -0.107863210 0.964607596
1403636682213555456 6.585473061 -1.845627308 8.874723434 -0.003580488 -0.241586238 -0.107072458 0.964447379
1403636682263555584 6.555579185 -1.841042995 8.850257874 -0.007639568 -0.241978094 -0.106190570 0.964423060
1403636682313555456 6.525528908 -1.833540916 8.824544907 -0.013121380 -0.241873503 -0.107505776 0.964244545
1403636682363555584 6.501109123 -1.827671289 8.795473099 -0.019414345 -0.241916746 -0.107058518 0.964177310
1403636682413555456 6.473019600 -1.819897890 8.775959969 -0.022648036 -0.241582081 -0.107891321 0.964097798
1403636682463555584 6.451354980 -1.817569375 8.742874146 -0.021299765 -0.241538465 -0.106533103 0.964290500
1403636682513555456 6.421405792 -1.807993054 8.721905708 -0.016592523 -0.240868509 -0.108103484 0.964375794
1403636682563555584 6.396085739 -1.799063206 8.696786880 -0.011957545 -0.239817873 -0.107990697 0.964718819
1403636682613555456 6.370105743 -1.784423828 8.676061630 -0.007174152 -0.239071488 -0.108892523 0.964850128
1403636682663555584 6.344564438 -1.783938408 8.641395569 -0.004665502 -0.237785310 -0.108854987 0.965187550
1403636682713555456 6.317990303 -1.773951650 8.614770889 -0.002544165 -0.237996534 -0.106934838 0.965358019
1403636682763555584 6.291951656 -1.767612219 8.590858459 -0.000840955 -0.238002077 -0.104802079 0.965593517
1403636682813555456 6.266599655 -1.760689616 8.563728333 0.001735570 -0.237451434 -0.103783168 0.965837896
1403636682863555584 6.239103794 -1.751383543 8.539337158 0.003637826 -0.236237988 -0.104764760 0.966024160
1403636682913555456 6.213412285 -1.747780204 8.509407043 0.004309550 -0.234396681 -0.107065044 0.966217697
1403636682963555584 6.190203667 -1.743076682 8.475803375 0.004680072 -0.233023793 -0.110211581 0.966194272
1403636683013555456 6.164353371 -1.738970518 8.445644379 0.005411464 -0.231941119 -0.112840459 0.966147542
1403636683063555584 6.138592243 -1.733389258 8.415403366 0.006794406 -0.231931388 -0.112753823 0.966151237
1403636683113555456 6.113255978 -1.726049304 8.385044098 0.005566294 -0.232174158 -0.112615652 0.966116905
1403636683163555584 6.088788986 -1.720556498 8.346834183 0.004682454 -0.234077200 -0.111296073 0.965815246
1403636683213555456 6.054003716 -1.710539818 8.321682930 0.002610448 -0.234266862 -0.110513769 0.965866923
1403636683263555584 6.026851654 -1.700807691 8.288856506 0.001460489 -0.234918714 -0.109514266 0.965824902
1403636683313555456 6.000306129 -1.691240430 8.259101868 0.000208675 -0.236610219 -0.108399928 0.965538681
1403636683363555584 5.970305920 -1.674155235 8.221080780 -0.000292468 -0.237504095 -0.107399769 0.965430975
1403636683413555456 5.946114540 -1.658762455 8.198395729 -0.000966801 -0.238913134 -0.106326453 0.965201676
1403636683463555584 5.913937569 -1.641170621 8.162508011 -0.001622575 -0.239679277 -0.105879784 0.965059936
1403636683513555456 5.893418312 -1.624017835 8.136697769 -0.001654040 -0.241042539 -0.105653927 0.964745045
1403636683563555584 5.868923664 -1.609182477 8.109481812 -0.002352716 -0.242212117 -0.105393708 0.964479089
1403636683613555456 5.842842102 -1.584511042 8.075838089 -0.003018084 -0.242548689 -0.105741039 0.964354634
1403636683663555584 5.819989204 -1.572318435 8.049633980 -0.006569908 -0.244141519 -0.105094962 0.964005589
1403636683713555456 5.791540623 -1.551004529 8.017379761 -0.009008220 -0.244025245 -0.105837226 0.963934124
1403636683763555584 5.766362190 -1.535811424 7.979250431 -0.012188775 -0.244354427 -0.105217211 0.963883638
1403636683813555456 5.742933750 -1.518182516 7.949232101 -0.015352831 -0.245337799 -0.106529780 0.963444352
1403636683863555584 5.718191624 -1.504009128 7.918719292 -0.018470295 -0.246986717 -0.104320399 0.963210106
1403636683913555456 5.691407681 -1.492249250 7.882205009 -0.018322170 -0.246514097 -0.107193150 0.963018537
1403636683963555584 5.666541100 -1.479580522 7.850517750 -0.017854892 -0.247446969 -0.106702164 0.962842584
1403636684013555456 5.640500546 -1.473909378 7.816829681 -0.016575063 -0.248188764 -0.105758101 0.962778687
1403636684063555584 5.618048191 -1.470534086 7.783004761 -0.014931565 -0.249288961 -0.105944604 0.962500811
1403636684113555456 5.595675945 -1.465253353 7.751339912 -0.013030956 -0.250431001 -0.105821893 0.962245405
1403636684163555584 5.567684650 -1.459314704 7.720099926 -0.011707364 -0.251339018 -0.106263787 0.961976945
1403636684213555456 5.546120644 -1.456726432 7.690803528 -0.010254675 -0.252763003 -0.105672069 0.961685538
1403636684263555584 5.519622803 -1.457676411 7.654530525 -0.009081583 -0.253999323 -0.105135456 0.961430371
1403636684313555456 5.498003483 -1.454913735 7.623031616 -0.006479908 -0.255062908 -0.105226077 0.961159945
1403636684363555584 5.474683285 -1.458150864 7.586378098 -0.005291460 -0.255610734 -0.104903176 0.961056948
1403636684413555456 5.451189041 -1.453186274 7.553341866 -0.003714749 -0.256650835 -0.105737656 0.960695624
1403636684463555584 5.430026054 -1.448100805 7.517254829 -0.003034124 -0.257704407 -0.104585171 0.960542142
1403636684513555456 5.403407574 -1.444708705 7.482280254 -0.003906522 -0.258709043 -0.101264775 0.960624695
1403636684563555584 5.382610798 -1.433307528 7.459790230 -0.002799290 -0.259554446 -0.099093243 0.960626960
1403636684613555456 5.365495205 -1.420185924 7.436344624 -0.002190850 -0.261169285 -0.097233772 0.960380852
1403636684663555584 5.350407600 -1.410627484 7.412376404 -0.001724704 -0.262496412 -0.096923664 0.960051298
1403636684713555456 5.330203533 -1.400977015 7.376489639 -0.001314773 -0.262587696 -0.096129917 0.960106790
1403636684763555584 5.310234547 -1.386587262 7.346294403 -0.000536572 -0.262066126 -0.097000696 0.960162461
1403636684813555456 5.292347908 -1.369798064 7.308547020 -0.000132774 -0.261755824 -0.096707612 0.960276783
1403636684863555584 5.277008057 -1.352246881 7.277701855 -0.000323781 -0.261914730 -0.098590299 0.960041940
1403636684913555456 5.261731148 -1.335735798 7.249485970 0.001067118 -0.260448694 -0.101319335 0.960156083
1403636684963555584 5.247983456 -1.318448544 7.221862793 0.001042331 -0.258279383 -0.106702745 0.960158944
1403636685013555456 5.236080647 -1.300913095 7.193097115 0.001248189 -0.256651551 -0.110381603 0.960179329
1403636685063555584 5.224619865 -1.284503818 7.165467262 0.000984544 -0.255518794 -0.112504862 0.960235298
1403636685113555456 5.207767487 -1.271121979 7.132018089 -0.000576742 -0.253966570 -0.113294907 0.960554481
1403636685163555584 5.198466301 -1.262727976 7.098110199 -0.003605164 -0.253581733 -0.113052242 0.960678101
1403636685213555456 5.184470654 -1.252039433 7.062207699 -0.005331364 -0.251162857 -0.115321763 0.961035728
1403636685263555584 5.171534538 -1.243667841 7.028731823 -0.006813110 -0.249082819 -0.117925510 0.961251736
1403636685313555456 5.158366203 -1.234943509 6.994832993 -0.007649450 -0.247149423 -0.120310374 0.961448967
1403636685363555584 5.148695946 -1.227629900 6.961056709 -0.007760806 -0.245657980 -0.120575264 0.961796999
1403636685413555456 5.130470753 -1.222653747 6.925076962 -0.008087228 -0.244369879 -0.120763339 0.962098837
1403636685463555584 5.117115974 -1.213210464 6.891647339 -0.008647423 -0.244074792 -0.118290231 0.962476075
1403636685513555456 5.101458073 -1.204070091 6.855846405 -0.009282628 -0.243977576 -0.116499551 0.962713122
1403636685563555584 5.083722591 -1.195036173 6.822792053 -0.010720206 -0.243599489 -0.115499295 0.962914467
1403636685613555456 5.071119785 -1.182399869 6.786718369 -0.010464292 -0.243785977 -0.112363681 0.963241041
1403636685663555584 5.052913666 -1.170284271 6.755508423 -0.010161941 -0.242692620 -0.112855420 0.963462889
1403636685713555456 5.040475845 -1.154124260 6.718632698 -0.008544290 -0.242557481 -0.113824643 0.963398576
1403636685763555584 5.026255131 -1.136432052 6.689704895 -0.007687746 -0.242456615 -0.114520863 0.963348687
1403636685813555456 5.008135319 -1.117097616 6.654745579 -0.005519233 -0.241109341 -0.116571821 0.963455677
1403636685863555584 4.994710922 -1.100419402 6.627602577 -0.003864835 -0.241056725 -0.117866933 0.963319302
1403636685913555456 4.978308678 -1.079662204 6.595801353 -0.004354926 -0.241387144 -0.116960727 0.963344932
1403636685963555584 4.954041004 -1.056198835 6.561903954 -0.005820727 -0.241743594 -0.114221327 0.963576496
1403636686013555456 4.938501358 -1.038233995 6.526234627 -0.008416330 -0.243070334 -0.111646950 0.963525295
1403636686063555584 4.922407627 -1.023349881 6.493138313 -0.012455165 -0.244461939 -0.109144136 0.963416219
1403636686113555456 4.906594276 -1.007795811 6.459669113 -0.014649848 -0.245373949 -0.106714554 0.963425636
1403636686163555584 4.886628151 -0.990683556 6.426933765 -0.014195380 -0.245067909 -0.106380798 0.963547289
1403636686213555456 4.872643471 -0.977123737 6.393711090 -0.015019181 -0.245848998 -0.105114371 0.963474751
1403636686263555584 4.854532242 -0.969434917 6.356010437 -0.016842552 -0.245949492 -0.103692405 0.963573039
1403636686313555456 4.836400032 -0.956644058 6.317894459 -0.017344361 -0.245635271 -0.103483729 0.963666737
1403636686363555584 4.821450233 -0.950387120 6.288137436 -0.019029761 -0.245912239 -0.102868348 0.963630140
1403636686413555456 4.803427696 -0.943698406 6.254950523 -0.020056445 -0.245677322 -0.103755526 0.963574111
1403636686463555584 4.783500195 -0.933915138 6.223167896 -0.021514304 -0.245279059 -0.103377342 0.963684797
1403636686513555456 4.765254498 -0.926078260 6.188489914 -0.023306098 -0.245369643 -0.103321485 0.963626087
1403636686563555584 4.753689766 -0.917631030 6.158382416 -0.023212854 -0.245729461 -0.103478156 0.963519871
1403636686613555456 4.732865334 -0.905497313 6.129185200 -0.023080960 -0.245462969 -0.105048276 0.963420987
1403636686663555584 4.719790936 -0.891430259 6.101449490 -0.022760946 -0.245670170 -0.105443701 0.963332653
1403636686713555456 4.702500820 -0.878846288 6.074143410 -0.022553718 -0.246047616 -0.105179496 0.963270009
1403636686763555584 4.685632229 -0.867030382 6.047496796 -0.021344431 -0.246548742 -0.104466870 0.963247001
1403636686813555456 4.666479588 -0.854607105 6.018145561 -0.019219873 -0.246155933 -0.104264982 0.963414073
1403636686863555584 4.646971703 -0.843888342 5.993685246 -0.018418854 -0.247161821 -0.102862112 0.963322997
1403636686913555456 4.634119987 -0.834432125 5.968351841 -0.017075047 -0.248052463 -0.102569625 0.963149965
1403636686963555584 4.616277695 -0.828189135 5.944227695 -0.016473899 -0.248530641 -0.101890244 0.963109314
1403636687013555456 4.602544785 -0.820830286 5.916468620 -0.015114568 -0.249378458 -0.101010643 0.963005066
1403636687063555584 4.588398933 -0.819952011 5.889151096 -0.015174778 -0.249877870 -0.099865235 0.962994158
1403636687113555456 4.569022179 -0.820316851 5.864964485 -0.015986191 -0.249918625 -0.100539990 0.962900221
1403636687163555584 4.553297997 -0.817390323 5.838695049 -0.015292400 -0.249969438 -0.100458376 0.962906837
1403636687213555456 4.544854164 -0.813893914 5.813220024 -0.013422487 -0.250771403 -0.099843286 0.962790132
1403636687263555584 4.527276993 -0.807972372 5.789294243 -0.012729670 -0.250691801 -0.100533843 0.962748408
1403636687313555456 4.513419151 -0.809440434 5.762748718 -0.012697543 -0.251078248 -0.101044044 0.962594688
1403636687363555584 4.496911526 -0.799078166 5.742973804 -0.010386808 -0.250547856 -0.101425461 0.962720454
1403636687413555456 4.484173775 -0.792162180 5.716707706 -0.008876031 -0.250763357 -0.102202460 0.962597311
1403636687463555584 4.470547676 -0.779392004 5.699357986 -0.007634303 -0.250907600 -0.102153867 0.962575555
1403636687513555456 4.457307816 -0.769169509 5.676740646 -0.006993045 -0.251005501 -0.101861008 0.962585926
1403636687563555584 4.447773457 -0.757608294 5.658452988 -0.007518001 -0.252397358 -0.101031110 0.962305427
1403636687613555456 4.435626030 -0.747697532 5.635293007 -0.007062723 -0.252668858 -0.100412853 0.962302387
1403636687663555584 4.424726486 -0.729324102 5.612729073 -0.006786821 -0.253611028 -0.098594487 0.962244511
1403636687713555456 4.414609909 -0.710924804 5.594089508 -0.005515662 -0.254659921 -0.096796833 0.962158144
1403636687763555584 4.404146671 -0.697110355 5.573965549 -0.006553760 -0.255048841 -0.097126648 0.962015390
1403636687813555456 4.393922806 -0.671483278 5.557414055 -0.006226371 -0.255162537 -0.097591281 0.961940348
1403636687863555584 4.389045715 -0.657023966 5.535004616 -0.007102882 -0.255609155 -0.097907141 0.961783588
1403636687913555456 4.379275322 -0.629565835 5.516862869 -0.006681138 -0.254994661 -0.099293910 0.961807549
1403636687963555584 4.372709751 -0.605638564 5.498320580 -0.006452012 -0.254058778 -0.101850323 0.961789489
1403636688013555456 4.364065647 -0.582381666 5.480872154 -0.005468514 -0.253646016 -0.104167521 0.961656332
1403636688063555584 4.355463505 -0.556198001 5.466939926 -0.005136523 -0.252886117 -0.107926421 0.961443782
1403636688113555456 4.347402573 -0.532540262 5.448889732 -0.004656544 -0.251548320 -0.110496901 0.961505175
1403636688163555584 4.343976498 -0.511852920 5.429849625 -0.004410527 -0.251777321 -0.111168705 0.961368978
1403636688213555456 4.331487179 -0.488994062 5.413219929 -0.004680471 -0.251259774 -0.111479722 0.961467087
1403636688263555584 4.322184563 -0.471392006 5.393057823 -0.004558920 -0.251756102 -0.110090762 0.961497843
1403636688313555456 4.314930439 -0.454098314 5.370856285 -0.005987623 -0.252613902 -0.107672818 0.961538851
1403636688363555584 4.306325912 -0.434459507 5.351648331 -0.006574346 -0.253419578 -0.105580017 0.961555064
1403636688413555456 4.300862789 -0.420142055 5.327749252 -0.008692178 -0.253886014 -0.105616063 0.961411238
1403636688463555584 4.289581776 -0.400207758 5.310502052 -0.007744717 -0.252813876 -0.106834121 0.961567283
1403636688513555456 4.283749580 -0.381101668 5.287228107 -0.007962659 -0.252054691 -0.110159360 0.961389601
1403636688563555584 4.283474922 -0.360836446 5.267736435 -0.007159265 -0.251397222 -0.113962799 0.961124718
1403636688613555456 4.272234917 -0.339790165 5.246572495 -0.007141048 -0.249764785 -0.119187564 0.960916698
1403636688663555584 4.262430668 -0.315460682 5.230376244 -0.006795153 -0.248992220 -0.121232219 0.960863888
1403636688713555456 4.256518841 -0.293195665 5.210084915 -0.006240424 -0.249504045 -0.123031341 0.960506141
1403636688763555584 4.247197628 -0.266701281 5.190613747 -0.005974459 -0.250000119 -0.123929873 0.960263312
1403636688813555456 4.239748001 -0.239588857 5.167606354 -0.006154134 -0.251783699 -0.122238986 0.960012853
1403636688863555584 4.232632637 -0.219026610 5.145046234 -0.007476804 -0.254222393 -0.122436784 0.959335327
1403636688913555456 4.206826210 -0.201109797 5.125482559 -0.010428506 -0.256628931 -0.123668425 0.958508670
1403636688963555584 4.192692757 -0.179835469 5.101248264 -0.012149857 -0.260055631 -0.121769711 0.957807660
1403636689013555456 4.176052094 -0.164233804 5.074378967 -0.014363071 -0.263242304 -0.120727502 0.957038164
1403636689063555584 4.174964905 -0.148350582 5.050959110 -0.015430167 -0.269184232 -0.117158003 0.955811620
1403636689113555456 4.147990227 -0.137148678 5.026968002 -0.018099140 -0.271940768 -0.117053293 0.954996943
1403636689163555584 4.132192612 -0.127488732 5.005732059 -0.021008011 -0.275617957 -0.116631344 0.953934252
1403636689213555456 4.112701416 -0.121661395 4.978415489 -0.023182230 -0.278233379 -0.118631490 0.952877402
1403636689263555584 4.096162796 -0.113945365 4.953376293 -0.024487823 -0.280862272 -0.117749564 0.952182591
1403636689313555456 4.079837799 -0.109722838 4.930945873 -0.026426533 -0.283457726 -0.118149169 0.951311767
1403636689363555584 4.059221268 -0.108854219 4.906398296 -0.026618956 -0.284927815 -0.118860073 0.950778544
1403636689413555456 4.048611641 -0.106267452 4.884944439 -0.025897857 -0.287443489 -0.118563235 0.950078070
1403636689463555584 4.029958248 -0.107689828 4.857662678 -0.025391294 -0.288759381 -0.118901417 0.949650288
1403636689513555456 4.003456116 -0.108428597 4.837953091 -0.025999399 -0.288753152 -0.119716160 0.949533403
1403636689563555584 3.998939276 -0.117691219 4.813404083 -0.027864981 -0.291459322 -0.118421383 0.948815763
1403636689613555456 3.972420454 -0.122320667 4.792468548 -0.030628653 -0.290292233 -0.118388131 0.949092507
1403636689663555584 3.958810329 -0.130097359 4.769906044 -0.034143701 -0.292311311 -0.116132349 0.948631406
1403636689713555456 3.938607931 -0.144335777 4.754131794 -0.040230136 -0.293329984 -0.114834487 0.948236287
1403636689763555584 3.919955254 -0.148790628 4.735431671 -0.046089087 -0.293935746 -0.109944209 0.948361635
1403636689813555456 3.895849705 -0.156086057 4.717286110 -0.049947888 -0.293787003 -0.108079970 0.948426664
1403636689863555584 3.882677555 -0.162756473 4.706358433 -0.050611835 -0.295227855 -0.103802525 0.948421836
1403636689913555456 3.862219334 -0.165029407 4.691558361 -0.049882803 -0.295904696 -0.096487649 0.949021757
1403636689963555584 3.841685295 -0.172420621 4.682848930 -0.048990950 -0.296044856 -0.093339279 0.949339271
1403636690013555456 3.825437069 -0.173663899 4.676777840 -0.046940327 -0.295746595 -0.091627233 0.949702621
1403636690063555584 3.804160595 -0.183777228 4.671271801 -0.047014084 -0.293664545 -0.093418933 0.950170398
1403636690113555456 3.798387766 -0.189167649 4.672004700 -0.047938760 -0.293487132 -0.098677449 0.949647248
1403636690163555584 3.776352644 -0.185360461 4.669129372 -0.045613769 -0.288692147 -0.103682794 0.950697720
1403636690213555456 3.769752264 -0.196656495 4.673946381 -0.046232942 -0.288038552 -0.109136291 0.950255513
1403636690263555584 3.751245499 -0.198864877 4.678831100 -0.044117104 -0.286704808 -0.110920958 0.950552762
1403636690313555456 3.736880541 -0.209434241 4.678144455 -0.042850692 -0.284835070 -0.113802321 0.950832188
1403636690363555584 3.717937469 -0.223173738 4.684848785 -0.042652499 -0.284080893 -0.116539732 0.950735152
1403636690413555456 3.699845314 -0.234564006 4.695118904 -0.041375093 -0.283687443 -0.117371760 0.950806737
1403636690463555584 3.685275078 -0.247554153 4.705420494 -0.040721372 -0.284624696 -0.116021514 0.950720549
1403636690513555456 3.666595221 -0.258337796 4.708778381 -0.040002611 -0.284451365 -0.111545011 0.951338530
1403636690563555584 3.654030561 -0.273411036 4.720016956 -0.040133480 -0.286369622 -0.107959099 0.951171160
1403636690613555456 3.645941734 -0.279567808 4.725217342 -0.040471323 -0.288594097 -0.100705974 0.951280117
1403636690663555584 3.627254009 -0.291170061 4.740454674 -0.040909320 -0.290284932 -0.095347457 0.951299071
1403636690713555456 3.616532803 -0.296788692 4.750396252 -0.039310906 -0.293181717 -0.084967881 0.951461792
1403636690763555584 3.607869148 -0.296061218 4.767734051 -0.037691697 -0.296857834 -0.072451726 0.951422870
1403636690813555456 3.587026358 -0.303476900 4.789958000 -0.037224527 -0.298772871 -0.066830628 0.951253235
1403636690863555584 3.576410770 -0.300758481 4.811909199 -0.033174690 -0.300753772 -0.059983168 0.951235294
1403636690913555456 3.570553780 -0.302618295 4.834795952 -0.028320085 -0.302694649 -0.055075638 0.951073349
1403636690963555584 3.566940784 -0.300795734 4.860713005 -0.020513836 -0.304752469 -0.048649922 0.950967014
1403636691013555456 3.566433191 -0.302818060 4.886842728 -0.011413462 -0.306969553 -0.044486616 0.950610518
1403636691063555584 3.568048477 -0.303803414 4.910394192 -0.002513452 -0.307644486 -0.041108619 0.950609624
1403636691113555456 3.575553894 -0.309482813 4.937305927 0.003461243 -0.308322817 -0.041363731 0.950375795
1403636691163555584 3.584891558 -0.318196416 4.964089870 0.010737557 -0.307689667 -0.044581544 0.950381100
1403636691213555456 3.603361607 -0.326581001 4.989445686 0.018569501 -0.306593120 -0.052834716 0.950191736
1403636691263555584 3.624264240 -0.338749379 5.013166904 0.025299698 -0.303614885 -0.064167649 0.950294912
1403636691313555456 3.648595572 -0.347470194 5.035750866 0.029606633 -0.300686091 -0.074787140 0.950325310
1403636691363555584 3.675520420 -0.359099597 5.055932045 0.030619692 -0.298855096 -0.084298521 0.950074613
1403636691413555456 3.703168869 -0.368848354 5.073529243 0.024873298 -0.298064917 -0.089317210 0.950032115
1403636691463555584 3.735321045 -0.385831684 5.085703373 0.015844196 -0.297065228 -0.094822749 0.950005174
1403636691513555456 3.768895626 -0.402165800 5.097774029 0.007681616 -0.298179656 -0.097411558 0.949495077
1403636691563555584 3.801374912 -0.416394204 5.109705448 0.003511181 -0.298981309 -0.097700901 0.949237764
1403636691613555456 3.834300518 -0.436703503 5.120497227 -0.001015460 -0.299059927 -0.100725427 0.948902786
1403636691663555584 3.870619774 -0.463966310 5.128640175 -0.003567101 -0.298061132 -0.108567663 0.948345900
1403636691713555456 3.907477856 -0.481191278 5.137308598 -0.004531623 -0.296204597 -0.114640072 0.948208809
1403636691763555584 3.943386078 -0.502141237 5.149579048 -0.003985589 -0.295199424 -0.120506980 0.947797179
1403636691813555456 3.973299026 -0.524950385 5.158024788 -0.005828583 -0.294594169 -0.123539031 0.947585583
1403636691863555584 4.010546684 -0.542413116 5.164341927 -0.007142249 -0.295532018 -0.122808479 0.947379529
1403636691913555456 4.050967693 -0.554342508 5.172872543 -0.006833761 -0.296855628 -0.118900895 0.947466433
1403636691963555584 4.083861351 -0.566925347 5.185008049 -0.003217302 -0.298440248 -0.114028998 0.947586656
1403636692013555456 4.114737988 -0.580688238 5.190073967 0.000276920 -0.298675537 -0.111363791 0.947834909
1403636692063555584 4.147023201 -0.593818843 5.201115131 0.000240499 -0.299549639 -0.109439641 0.947783172
1403636692113555456 4.191596031 -0.608364582 5.204906464 -0.000146150 -0.299101979 -0.110283501 0.947826743
1403636692163555584 4.217418671 -0.622796893 5.213541031 0.000926892 -0.296235055 -0.116243839 0.948014379
1403636692213555456 4.257684708 -0.638489783 5.217277050 0.000381588 -0.295219362 -0.118426755 0.948061466
1403636692263555584 4.289735317 -0.658481121 5.224450111 -0.001485537 -0.294226199 -0.121155538 0.948024333
1403636692313555456 4.319394112 -0.674851716 5.225088120 -0.002232688 -0.293650925 -0.120989278 0.948222399
1403636692363555584 4.358541012 -0.697370529 5.227877617 -0.003746764 -0.294862926 -0.117598422 0.948268116
1403636692413555456 4.389704227 -0.715958714 5.227710724 -0.005038637 -0.293661416 -0.118151359 0.948566198
1403636692463555584 4.419009686 -0.738394260 5.227791309 -0.005309739 -0.291777283 -0.121098913 0.948774397
1403636692513555456 4.461556435 -0.765730441 5.226103783 -0.004578854 -0.290459424 -0.124971107 0.948680401
1403636692563555584 4.491451263 -0.791271806 5.224111080 -0.004141231 -0.289473057 -0.125018746 0.948977590
1403636692613555456 4.526569843 -0.822075307 5.219511032 -0.005066930 -0.289671123 -0.124148913 0.949026883
1403636692663555584 4.555568695 -0.852763474 5.212828636 -0.006026788 -0.288647860 -0.122863308 0.949500203
1403636692713555456 4.590685844 -0.884083033 5.209696293 -0.008055731 -0.287562728 -0.126623839 0.949320376
1403636692763555584 4.612082958 -0.905820131 5.207969666 -0.009286130 -0.283052295 -0.134383336 0.949597955
1403636692813555456 4.648055077 -0.929159701 5.199275494 -0.010198022 -0.279240966 -0.143879265 0.949325681
1403636692863555584 4.673248291 -0.948967516 5.197641373 -0.010725887 -0.276354581 -0.150656164 0.949113190
1403636692913555456 4.702805042 -0.973749459 5.196571350 -0.011806854 -0.274687052 -0.155564472 0.948792577
1403636692963555584 4.728251457 -0.995974898 5.188091278 -0.013385178 -0.274564654 -0.156557575 0.948643684
1403636693013555456 4.753869534 -1.016418457 5.179392338 -0.015540167 -0.275856227 -0.153258830 0.948774755
1403636693063555584 4.772476673 -1.032522202 5.174174309 -0.015108746 -0.277079552 -0.149092734 0.949089050
1403636693113555456 4.787039757 -1.052276611 5.168835640 -0.014424828 -0.278571904 -0.145619541 0.949202061
1403636693163555584 4.800567627 -1.074992180 5.166677952 -0.015201768 -0.280339450 -0.142195717 0.949188650
1403636693213555456 4.820603848 -1.085980415 5.159600735 -0.016604066 -0.281495064 -0.140319794 0.949102283
1403636693263555584 4.830322266 -1.103515267 5.157388687 -0.021767516 -0.282181591 -0.139059395 0.948979557
1403636693313555456 4.848487854 -1.109594107 5.151345730 -0.026343031 -0.283491403 -0.135844573 0.948938847
1403636693363555584 4.860880852 -1.117800951 5.148742199 -0.030968467 -0.284431010 -0.134049997 0.948773205
1403636693413555456 4.874116421 -1.124006271 5.145236969 -0.035065420 -0.285713673 -0.131519645 0.948599339
1403636693463555584 4.887464523 -1.134965181 5.145801544 -0.040319528 -0.286925524 -0.130433589 0.948174655
1403636693513555456 4.897827148 -1.141059399 5.142454624 -0.046883237 -0.286763549 -0.129407123 0.948062479
1403636693563555584 4.907931328 -1.153260350 5.145433426 -0.054079358 -0.286922932 -0.130396947 0.947495282
1403636693613555456 4.916180611 -1.155151606 5.149174213 -0.057954825 -0.286828369 -0.131749779 0.947107553
1403636693663555584 4.924037933 -1.159625888 5.154212952 -0.060258463 -0.286958963 -0.131495759 0.946959496
1403636693713555456 4.934271812 -1.168776631 5.158477783 -0.059154499 -0.287845403 -0.130796462 0.946856916
1403636693763555584 4.934758663 -1.176641941 5.169531345 -0.053552471 -0.288572550 -0.130086944 0.947066724
1403636693813555456 4.935597897 -1.183675528 5.178673267 -0.048023675 -0.289087862 -0.129981816 0.947220504
1403636693863555584 4.936367035 -1.193416834 5.190919399 -0.041182354 -0.289980739 -0.128258541 0.947504580
1403636693913555456 4.935220718 -1.205825210 5.205018044 -0.033731204 -0.291399211 -0.125570193 0.947723985
1403636693963555584 4.931805611 -1.209546804 5.218925476 -0.025781762 -0.291883647 -0.124610305 0.947951198
1403636694013555456 4.937000275 -1.213108540 5.235600471 -0.017545717 -0.293935418 -0.120963790 0.947977781
1403636694063555584 4.932942390 -1.220543027 5.250106335 -0.011736508 -0.294311285 -0.120236225 0.948043466
1403636694113555456 4.937567234 -1.226033330 5.264601231 -0.009065642 -0.295436978 -0.119082406 0.947868228
1403636694163555584 4.933733463 -1.232619882 5.280653000 -0.006336580 -0.295712411 -0.118742689 0.947847128
1403636694213555456 4.935015678 -1.236596584 5.291791916 -0.004415122 -0.296070635 -0.118199773 0.947814047
1403636694263555584 4.936281204 -1.241552114 5.306710243 -0.004406641 -0.296053171 -0.118652388 0.947763026
1403636694313555456 4.934346199 -1.253497720 5.314693451 -0.006392884 -0.296015412 -0.119951949 0.947599888
1403636694363555584 4.935245037 -1.260459423 5.323825836 -0.009123040 -0.296124697 -0.119126663 0.947647512
1403636694413555456 4.937238693 -1.272810698 5.331930161 -0.012298382 -0.295866221 -0.120785937 0.947482288
1403636694463555584 4.936151505 -1.280991554 5.343842506 -0.014552352 -0.295379400 -0.121078908 0.947564840
1403636694513555456 4.934648991 -1.288101435 5.353724480 -0.015659731 -0.294523060 -0.122816004 0.947590232
1403636694563555584 4.934554100 -1.297225714 5.364788532 -0.016924884 -0.294437796 -0.123143263 0.947552443
1403636694613555456 4.936411381 -1.299993753 5.376695156 -0.017412482 -0.294027686 -0.122998379 0.947689831
1403636694663555584 4.939508438 -1.303348660 5.388114452 -0.017421059 -0.293707460 -0.123328775 0.947745979
1403636694713555456 4.937629223 -1.310416937 5.399820328 -0.016570788 -0.293082118 -0.124236844 0.947836220
1403636694763555584 4.940942764 -1.311472774 5.412403107 -0.014935887 -0.293883741 -0.121000089 0.948033869
1403636694813555456 4.941142082 -1.313351750 5.425244331 -0.013364041 -0.293513805 -0.120207965 0.948272705
1403636694863555584 4.939612865 -1.308828592 5.437627792 -0.014883881 -0.294860154 -0.113969222 0.948602617
1403636694913555456 4.945966721 -1.308692336 5.450552940 -0.016260078 -0.296226293 -0.109120935 0.948724508
1403636694963555584 4.943402767 -1.308149099 5.462986946 -0.018428581 -0.296770930 -0.104640223 0.949019372
1403636695013555456 4.944611549 -1.308436036 5.477934837 -0.020272788 -0.296942532 -0.103084385 0.949098408
1403636695063555584 4.946887493 -1.306686282 5.492461205 -0.021205775 -0.295511663 -0.104832381 0.949333131
1403636695113555456 4.948543549 -1.304152012 5.506082535 -0.019783584 -0.293619841 -0.107603185 0.949640751
1403636695163555584 4.956021786 -1.302134871 5.519901276 -0.019183993 -0.292496145 -0.109098434 0.949829221
1403636695213555456 4.961451530 -1.308244348 5.531081200 -0.018204900 -0.290617257 -0.111920476 0.950096846
1403636695263555584 4.966608524 -1.306274176 5.548660278 -0.015655877 -0.289074063 -0.114159636 0.950346589
1403636695313555456 4.968851089 -1.315616965 5.561901569 -0.014784588 -0.287565440 -0.116293870 0.950559497
1403636695363555584 4.974614143 -1.323842287 5.571498871 -0.013710535 -0.286136359 -0.117755637 0.950826824
1403636695413555456 4.979447842 -1.331834078 5.581897736 -0.013226663 -0.285358578 -0.117683418 0.951076269
1403636695463555584 4.982401848 -1.341240883 5.595082283 -0.011987588 -0.284557223 -0.118280552 0.951258779
1403636695513555456 4.987450600 -1.352298260 5.604751587 -0.011085694 -0.283217311 -0.120637715 0.951373518
1403636695563555584 4.990941048 -1.362034321 5.615073681 -0.009547578 -0.282279223 -0.121883355 0.951510251
1403636695613555456 4.990891457 -1.365185142 5.626765728 -0.008208525 -0.280827612 -0.123598367 0.951731026
1403636695663555584 5.000177860 -1.374178767 5.637737751 -0.007169073 -0.279836923 -0.126302421 0.951676190
1403636695713555456 5.003930092 -1.377508640 5.646348953 -0.006214898 -0.279182941 -0.126277730 0.951878250
1403636695763555584 5.003767014 -1.378100038 5.656510353 -0.007504219 -0.279209584 -0.123369612 0.952242434
1403636695813555456 5.008365631 -1.385595798 5.665438652 -0.008774100 -0.279266775 -0.123254664 0.952229679
1403636695863555584 5.011319160 -1.384581566 5.676774025 -0.008853707 -0.279178739 -0.121918783 0.952426672
1403636695913555456 5.011786938 -1.384931564 5.685288429 -0.009999440 -0.278434426 -0.121874250 0.952638924
1403636695963555584 5.013766289 -1.382464290 5.692596912 -0.012215712 -0.278252453 -0.120813757 0.952801347
1403636696013555456 5.015318871 -1.380441070 5.703885555 -0.015112673 -0.278059632 -0.119721621 0.952953935
1403636696063555584 5.017620564 -1.374648333 5.711693764 -0.018336395 -0.277218372 -0.120917246 0.952991486
1403636696113555456 5.021645069 -1.375423670 5.720849037 -0.021978311 -0.275583982 -0.123879276 0.953007996
1403636696163555584 5.021500587 -1.367242098 5.733228683 -0.022603298 -0.273958832 -0.127182990 0.953026831
1403636696213555456 5.024045944 -1.359635115 5.740140915 -0.023132397 -0.272799909 -0.129063085 0.953093767
1403636696263555584 5.024832249 -1.353948116 5.751493454 -0.019845767 -0.272181362 -0.130448669 0.953156114
1403636696313555456 5.024986744 -1.351726294 5.759813786 -0.016814213 -0.272919446 -0.128888339 0.953215659
1403636696363555584 5.022197247 -1.344222546 5.771615505 -0.008829332 -0.273261547 -0.125606596 0.953662992
1403636696413555456 5.022163391 -1.340718627 5.781459808 -0.001404940 -0.274851114 -0.120384790 0.953919470
1403636696463555584 5.020536423 -1.335556984 5.788836956 0.002833210 -0.276268691 -0.114883415 0.954185188
1403636696513555456 5.014935970 -1.336689830 5.790754795 0.003818307 -0.275701940 -0.114336267 0.954411328
1403636696563555584 5.015557289 -1.336344123 5.797946453 0.002183879 -0.275855839 -0.113341749 0.954490721
1403636696613555456 5.012501240 -1.332873821 5.803084850 0.001574302 -0.275576860 -0.113075763 0.954603970
1403636696663555584 5.014252186 -1.333746433 5.806322575 -0.000747027 -0.275843889 -0.111679263 0.954692245
1403636696713555456 5.014024734 -1.331797004 5.807037830 -0.000860043 -0.276033849 -0.111458562 0.954663038
1403636696763555584 5.013973236 -1.334077954 5.808770657 -0.003148398 -0.275916308 -0.111757129 0.954657316
1403636696813555456 5.009535789 -1.330996037 5.811724663 -0.002958842 -0.274558365 -0.113203898 0.954878926
1403636696863555584 5.012369156 -1.331251740 5.810333252 -0.004113144 -0.274520487 -0.114002593 0.954790533
1403636696913555456 5.013651371 -1.324772000 5.811539173 -0.003431776 -0.273764014 -0.116098784 0.954757869
1403636696963555584 5.015377998 -1.320885897 5.812232018 -0.001726595 -0.271660209 -0.121859282 0.954645455
1403636697013555456 5.020499229 -1.316953182 5.812672615 -0.000123925 -0.269593179 -0.128624365 0.954345465
1403636697063555584 5.024176121 -1.311792254 5.807158470 0.001956044 -0.267318159 -0.134788007 0.954132795
1403636697113555456 5.023884296 -1.304784536 5.806509495 0.003640977 -0.264680803 -0.141924798 0.953828156
1403636697163555584 5.024675846 -1.302075267 5.801280022 0.005332347 -0.262636602 -0.147075683 0.953604877
1403636697213555456 5.020503998 -1.299766183 5.794209480 0.007078405 -0.261317372 -0.149789125 0.953533590
1403636697263555584 5.016265869 -1.297537446 5.785757065 0.007817545 -0.260434747 -0.150611654 0.953639746
1403636697313555456 5.012973309 -1.300163388 5.774370193 0.004797145 -0.261730373 -0.148509935 0.953634620
1403636697363555584 5.001190662 -1.303355813 5.758237362 0.000721881 -0.262919426 -0.142924964 0.954172552
1403636697413555456 4.988906384 -1.306113720 5.745658875 -0.003645283 -0.264773160 -0.137157992 0.954499602
1403636697463555584 4.976799488 -1.311356306 5.725860119 -0.008236322 -0.266142428 -0.132695675 0.954720974
1403636697513555456 4.967423916 -1.320907593 5.709892750 -0.012111807 -0.267098188 -0.129075885 0.954909086
1403636697563555584 4.955154896 -1.322277546 5.693271160 -0.013290591 -0.265632808 -0.126420006 0.955657125
1403636697613555456 4.944320679 -1.332841516 5.674341202 -0.013142151 -0.261986703 -0.125570416 0.956777036
1403636697663555584 4.931289673 -1.338732481 5.656675339 -0.012453052 -0.255882591 -0.124497592 0.958576739
1403636697713555456 4.917665482 -1.347243309 5.639970303 -0.013049928 -0.247773841 -0.121696755 0.961055517
1403636697763555584 4.906847000 -1.353379726 5.625146866 -0.014431304 -0.238028780 -0.119502202 0.963770330
1403636697813555456 4.888922691 -1.355354548 5.608035088 -0.014071044 -0.227064669 -0.116428852 0.966792643
1403636697863555584 4.874758720 -1.356095910 5.591984749 -0.013494468 -0.217171445 -0.112659082 0.969516575
1403636697913555456 4.864212036 -1.358365297 5.576705933 -0.014301932 -0.208747432 -0.108761922 0.971797705
1403636697963555584 4.852862835 -1.358120918 5.555459023 -0.014515371 -0.201362833 -0.104620516 0.973805308
1403636698013555456 4.833735943 -1.353503227 5.540239811 -0.014789100 -0.194181189 -0.101540655 0.975584149
1403636698063555584 4.818935394 -1.352289081 5.522691727 -0.014311900 -0.188691944 -0.099702150 0.976857185
1403636698113555456 4.801902294 -1.344482183 5.514005661 -0.014780032 -0.184444174 -0.096572332 0.977975309
1403636698163555584 4.783106804 -1.339559436 5.496427536 -0.015029825 -0.180543929 -0.093910433 0.978958011
1403636698213555456 4.762671471 -1.334831238 5.479307175 -0.014861258 -0.176593021 -0.091799967 0.979880989
1403636698263555584 4.743255138 -1.321790695 5.466252804 -0.014636243 -0.171541646 -0.088946119 0.981044233
1403636698313555456 4.724105358 -1.316114187 5.454165459 -0.015037432 -0.164698184 -0.087887406 0.982305527
1403636698363555584 4.713973999 -1.311123133 5.441010475 -0.015083197 -0.157723933 -0.085975930 0.983617663
1403636698413555456 4.689363956 -1.294109941 5.426836491 -0.014950508 -0.148432195 -0.083924986 0.985241592
1403636698463555584 4.676128864 -1.282575130 5.417194366 -0.016175430 -0.139859661 -0.079735927 0.986823082
1403636698513555456 4.652069569 -1.275375366 5.405874252 -0.017091578 -0.128992572 -0.078606412 0.988377333
1403636698563555584 4.633409500 -1.257336855 5.400070190 -0.017125443 -0.117713988 -0.073371723 0.990185201
1403636698613555456 4.609471321 -1.246375799 5.387119770 -0.017688628 -0.106131285 -0.070638582 0.991682112
1403636698663555584 4.592401981 -1.227292418 5.379455566 -0.018192194 -0.094616890 -0.065017454 0.993221700
1403636698713555456 4.573163986 -1.210269928 5.367442608 -0.018181516 -0.081912182 -0.059239700 0.994711280
1403636698763555584 4.551932335 -1.192464948 5.355573654 -0.018446866 -0.068622939 -0.054196492 0.995998621
1403636698813555456 4.534050941 -1.176645756 5.348182201 -0.019400427 -0.055114821 -0.048938010 0.997091293
1403636698863555584 4.510541439 -1.152193785 5.345896244 -0.019205526 -0.041721795 -0.041943323 0.998063743
1403636698913555456 4.485965252 -1.141443014 5.332652092 -0.019434022 -0.026909433 -0.037462559 0.998746574
1403636698963555584 4.471590996 -1.127064228 5.325932503 -0.019820863 -0.014232306 -0.029950086 0.999253511
1403636699013555456 4.444849014 -1.111500502 5.316158772 -0.019342855 -0.000609156 -0.023832474 0.999528587
1403636699063555584 4.420095921 -1.101278782 5.307815075 -0.019267818 0.012558266 -0.017995080 0.999573529
1403636699113555456 4.404119015 -1.090494394 5.304296970 -0.018020108 0.025269471 -0.010724806 0.999460697
1403636699163555584 4.388479233 -1.080501556 5.296205521 -0.016956216 0.037306987 -0.001349536 0.999159038
1403636699213555456 4.366168022 -1.077257037 5.282043457 -0.017600842 0.050931588 0.006561741 0.998525441
1403636699263555584 4.347320080 -1.072309494 5.277507782 -0.017577171 0.064662367 0.015014731 0.997639418
1403636699313555456 4.321326733 -1.062847018 5.261967659 -0.018409815 0.078578554 0.024024166 0.996448398
1403636699363555584 4.299035072 -1.063614130 5.250359535 -0.019173183 0.092588611 0.030988228 0.995037436
1403636699413555456 4.288759232 -1.069323421 5.238532543 -0.020002736 0.105251372 0.039712969 0.993450999
1403636699463555584 4.267728806 -1.078101635 5.225655556 -0.021134099 0.118506514 0.045794424 0.991671503
1403636699513555456 4.255611420 -1.079593658 5.217735767 -0.021574946 0.131111726 0.051480025 0.989794970
1403636699563555584 4.251540184 -1.065021276 5.229582310 -0.020196855 0.143013135 0.058393385 0.987790227
1403636699613555456 4.254169941 -1.073725700 5.197437286 -0.020631827 0.153946742 0.064361319 0.985764861
1403636699663555584 4.252997398 -1.070312977 5.177209377 -0.020069372 0.165398985 0.069935121 0.983539283
1403636699713555456 4.241906166 -1.070122361 5.179796696 -0.019009408 0.178196400 0.074912801 0.980955005
1403636699763555584 4.234669685 -1.062852144 5.171422005 -0.018651284 0.190374121 0.074914731 0.978671372
1403636699813555456 4.236337185 -1.049743176 5.168846130 -0.016729882 0.200896055 0.073536888 0.976705253
1403636699863555584 4.233441353 -1.046782732 5.164818287 -0.014717154 0.210008860 0.072732367 0.974879324
1403636699913555456 4.234835148 -1.041239381 5.151558876 -0.012818136 0.216207892 0.073068984 0.973524928
1403636699963555584 4.227841377 -1.035096407 5.151393414 -0.010946750 0.221505299 0.073584221 0.972317278
1403636700013555456 4.227419853 -1.025609732 5.150195599 -0.010212271 0.224602416 0.074805811 0.971521258
1403636700063555584 4.225572109 -1.015729070 5.148072720 -0.009919401 0.226995006 0.075333141 0.970927298
1403636700113555456 4.224112511 -1.003365517 5.140127182 -0.008735592 0.227834016 0.076548405 0.970647037
1403636700163555584 4.222710609 -0.989987314 5.142115593 -0.008056535 0.229658872 0.076919563 0.970193446
1403636700213555456 4.231592178 -0.980454922 5.135767460 -0.008081071 0.229543507 0.077643089 0.970162868
1403636700263555584 4.227095604 -0.966816187 5.131460190 -0.008415512 0.230676264 0.077687293 0.969887793
1403636700313555456 4.235581398 -0.947122216 5.134581089 -0.009218503 0.231917471 0.079896659 0.969404936
1403636700363555584 4.237710476 -0.933096409 5.120342731 -0.010944204 0.233918980 0.083168559 0.968630493
1403636700413555456 4.247250557 -0.916739464 5.124685287 -0.011825348 0.237661853 0.086582221 0.967409194
1403636700463555584 4.252995491 -0.894625187 5.121544361 -0.010107616 0.243419498 0.087293260 0.965932071
1403636700513555456 4.260270596 -0.871997416 5.111674786 -0.007299863 0.247558460 0.087362461 0.964898586
1403636700563555584 4.276033401 -0.856581330 5.110859871 -0.006052678 0.252751619 0.085798174 0.963700473
1403636700613555456 4.280545235 -0.830249906 5.110385895 -0.002595285 0.259614676 0.084328383 0.962019861
1403636700663555584 4.295371056 -0.811184883 5.102601528 -0.001701043 0.266830504 0.083170146 0.960146487
1403636700713555456 4.303193092 -0.790356994 5.101104736 -0.000443205 0.273935646 0.082899101 0.958168447
1403636700763555584 4.313331127 -0.760109842 5.103709698 0.001324665 0.280483484 0.082494631 0.956306398
1403636700813555456 4.323129654 -0.748119712 5.096528053 -0.000133467 0.285323024 0.082652725 0.954860866
1403636700863555584 4.337767124 -0.730283380 5.083393574 -0.002937538 0.288284451 0.083967686 0.953851640
1403636700913555456 4.343925953 -0.714854956 5.084457874 -0.005389833 0.291591287 0.084587000 0.952780426
1403636700963555584 4.355683327 -0.702167094 5.078181744 -0.009556424 0.293501139 0.085970402 0.952037215
1403636701013555456 4.375082970 -0.686980844 5.070382118 -0.011972322 0.293547422 0.087900884 0.951819301
1403636701063555584 4.381773949 -0.673048496 5.065999508 -0.016844388 0.294175416 0.088719830 0.951475680
1403636701113555456 4.392044067 -0.665215194 5.055446625 -0.021701308 0.293728054 0.089824975 0.951411784
1403636701163555584 4.401656628 -0.657017708 5.047855854 -0.023995433 0.293581754 0.088558756 0.951520503
1403636701213555456 4.410263538 -0.655828476 5.032377720 -0.026987379 0.292620689 0.089004204 0.951694846
1403636701263555584 4.422723293 -0.649748087 5.031654358 -0.027412662 0.291742682 0.088712581 0.951979458
1403636701313555456 4.438241005 -0.650166810 5.021861553 -0.028823188 0.290411711 0.087791368 0.952430010
1403636701363555584 4.448264599 -0.653467059 5.010378838 -0.028176030 0.289252460 0.087942496 0.952788174
1403636701413555456 4.458536148 -0.656190932 5.003795147 -0.026806448 0.288645059 0.085212663 0.953259826
1403636701463555584 4.471897602 -0.661165953 4.992439747 -0.024072252 0.287024230 0.083996624 0.953929901
1403636701513555456 4.488366127 -0.661062181 4.988067150 -0.019218361 0.285997689 0.082238108 0.954501390
1403636701563555584 4.500146866 -0.663812637 4.984275341 -0.015065957 0.285119027 0.078963295 0.955115139
1403636701613555456 4.518000603 -0.675508976 4.972960949 -0.013291528 0.283594370 0.077884026 0.955683887
1403636701663555584 4.536453247 -0.668637276 4.961585045 -0.010092620 0.281798691 0.075759530 0.956424654
1403636701713555456 4.548084259 -0.679665267 4.955046654 -0.009266527 0.281776279 0.075139284 0.956488550
1403636701763555584 4.560424805 -0.677045941 4.964097500 -0.008548007 0.283523023 0.075640187 0.955939412
1403636701813555456 4.583237648 -0.672189951 4.957322598 -0.008371146 0.285633743 0.077908531 0.955130100
1403636701863555584 4.592632771 -0.670508146 4.946205616 -0.009015379 0.291164875 0.079214983 0.953345001
1403636701913555456 4.607389450 -0.665734649 4.952877045 -0.009334671 0.297153294 0.083589621 0.951118052
1403636701963555584 4.624940395 -0.667380333 4.925016880 -0.009041849 0.302914232 0.087192841 0.948977649
1403636702013555456 4.638253212 -0.663528204 4.934430122 -0.009820978 0.311917871 0.090702124 0.945718706
1403636702063555584 4.643190861 -0.657661617 4.931324005 -0.008988485 0.321766227 0.095470764 0.941950679
1403636702113555456 4.671494484 -0.641004086 4.931121826 -0.007463459 0.331267476 0.098699324 0.938330770
1403636702163555584 4.690749645 -0.635513067 4.921948433 -0.006472460 0.341381103 0.103225447 0.934217155
1403636702213555456 4.697581768 -0.629431367 4.923632145 -0.006692758 0.351935178 0.106737323 0.929894626
1403636702263555584 4.716147423 -0.611337900 4.930721760 -0.007398658 0.360092014 0.109708376 0.926414073
1403636702313555456 4.737614632 -0.594680130 4.927471638 -0.009877751 0.367133677 0.112285860 0.923313200
1403636702363555584 4.748180866 -0.579854727 4.931786060 -0.012299820 0.373722792 0.113343246 0.920507073
1403636702413555456 4.772685528 -0.562683284 4.922718048 -0.014740034 0.378495693 0.113124110 0.918545961
1403636702463555584 4.782086849 -0.550220907 4.924736023 -0.018057445 0.383632481 0.114327915 0.916203678
1403636702513555456 4.797330379 -0.532064080 4.928030968 -0.020098751 0.387921512 0.112760179 0.914548039
1403636702563555584 4.814361572 -0.513184845 4.931292057 -0.021428233 0.390864104 0.113041468 0.913229287
1403636702613555456 4.829205036 -0.495596290 4.933769226 -0.023978420 0.393052459 0.113550916 0.912162840
1403636702663555584 4.847908020 -0.469815910 4.935705662 -0.026213342 0.394705564 0.113488294 0.911394954
1403636702713555456 4.862766266 -0.449086249 4.951389313 -0.027914360 0.396685630 0.112653688 0.910587966
1403636702763555584 4.878372192 -0.427088082 4.956975937 -0.028395293 0.396949649 0.113602877 0.910340071
1403636702813555456 4.897254467 -0.409016848 4.966982365 -0.031561371 0.397547543 0.113257900 0.910017848
1403636702863555584 4.923242569 -0.384982228 4.970634460 -0.032691501 0.396536589 0.113978975 0.910328984
1403636702913555456 4.940624237 -0.362375140 4.980791569 -0.033557780 0.396220118 0.114327744 0.910391510
1403636702963555584 4.956627369 -0.342218637 4.990639687 -0.033178829 0.395657063 0.114126101 0.910675526
1403636703013555456 4.980170250 -0.323828101 5.000140667 -0.030285642 0.394310832 0.115794152 0.911149561
1403636703063555584 4.990168571 -0.309270978 5.012342453 -0.027452912 0.394452780 0.115107752 0.911264777
1403636703113555456 5.006386757 -0.301023245 5.029031754 -0.022837646 0.393895656 0.117692642 0.911302984
1403636703163555584 5.026735783 -0.293187797 5.037004471 -0.014931302 0.392040700 0.120545201 0.911893606
1403636703213555456 5.048671246 -0.283207059 5.044503212 -0.009120959 0.389775544 0.123820916 0.912502170
1403636703263555584 5.064802170 -0.281370997 5.058314323 -0.003738925 0.388592005 0.127857685 0.912488163
1403636703313555456 5.084205151 -0.278280973 5.065413475 0.001620419 0.386760861 0.131858885 0.912702918
1403636703363555584 5.103446960 -0.275688708 5.066575050 0.004169384 0.385961026 0.132233083 0.912979245
1403636703413555456 5.128581524 -0.267400801 5.080778599 0.004222046 0.387707710 0.127427876 0.912922263
1403636703463555584 5.148109436 -0.267582834 5.082191944 0.000442744 0.389359623 0.122276984 0.912933290
1403636703513555456 5.168292522 -0.264010847 5.084299564 -0.003623115 0.390957862 0.116403170 0.913011014
1403636703563555584 5.189283371 -0.265528083 5.090229034 -0.007182571 0.392374545 0.111951187 0.912938952
1403636703613555456 5.212231159 -0.270579815 5.090098858 -0.011197696 0.392306089 0.110579617 0.913095117
1403636703663555584 5.232458591 -0.272661567 5.093304634 -0.013098433 0.392186314 0.110088207 0.913180649
1403636703713555456 5.249994278 -0.277124584 5.096735954 -0.014246705 0.392087638 0.110235512 0.913188040
1403636703763555584 5.270978928 -0.280073047 5.095145702 -0.013167831 0.391051292 0.110449217 0.913622737
1403636703813555456 5.291178226 -0.285143137 5.097596645 -0.011153694 0.389994502 0.112030171 0.913908660
1403636703863555584 5.319019318 -0.282185853 5.103372574 -0.007943277 0.388465673 0.112807721 0.914497554
1403636703913555456 5.336091042 -0.282883704 5.105647564 -0.005458671 0.387106210 0.114039041 0.914939404
1403636703963555584 5.356980801 -0.277339578 5.103715897 -0.003529112 0.385981172 0.114476763 0.915369391
1403636704013555456 5.373998165 -0.277297616 5.111608982 -0.002165683 0.385061502 0.115878232 0.915584624
1403636704063555584 5.390444279 -0.274486482 5.117448330 -0.001109090 0.383922398 0.116961129 0.915927112
1403636704113555456 5.419702053 -0.266613364 5.120063782 -0.002410226 0.382497817 0.118120536 0.916371703
1403636704163555584 5.430784225 -0.262572885 5.123353004 -0.005766321 0.382180184 0.117171317 0.916611135
1403636704213555456 5.454011440 -0.252402067 5.127694607 -0.009626250 0.381490529 0.116531417 0.916947544
1403636704263555584 5.467715263 -0.246574044 5.131925583 -0.013576608 0.381432027 0.115989350 0.916990638
1403636704313555456 5.492489815 -0.239521801 5.137782097 -0.016849285 0.381457299 0.115037739 0.917045653
1403636704363555584 5.508181572 -0.233200014 5.134945393 -0.019374071 0.381252319 0.113583393 0.917262316
1403636704413555456 5.527917385 -0.233487070 5.143250942 -0.021363851 0.380683184 0.113808036 0.917426646
1403636704463555584 5.571655750 -0.221948564 5.146299362 -0.023877375 0.379655302 0.112735525 0.917922854
1403636704513555456 5.586568356 -0.222881556 5.152866364 -0.026970251 0.380401343 0.110890172 0.917753100
1403636704563555584 5.604410648 -0.226310015 5.156431198 -0.029067099 0.380603492 0.111843579 0.917489588
1403636704613555456 5.624717236 -0.233154655 5.164670467 -0.031361651 0.380996615 0.112339303 0.917190194
1403636704663555584 5.656352997 -0.231478453 5.168166637 -0.032956086 0.380129308 0.112105124 0.917522788
1403636704713555456 5.673687935 -0.231520176 5.173308849 -0.037667613 0.379894525 0.111074291 0.917564094
1403636704763555584 5.699348450 -0.229853630 5.180005550 -0.040480595 0.379406482 0.111279882 0.917621315
1403636704813555456 5.729114532 -0.233637691 5.192187786 -0.044203568 0.377941310 0.113406919 0.917793691
1403636704863555584 5.751987934 -0.229468584 5.204269409 -0.047437649 0.377202809 0.113978289 0.917865276
1403636704913555456 5.776687622 -0.226339817 5.220630646 -0.050097916 0.376128107 0.115086973 0.918026567
1403636704963555584 5.811417103 -0.222493052 5.238220215 -0.053057402 0.374760300 0.115926653 0.918314040
1403636705013555456 5.835563183 -0.220338225 5.256411552 -0.055576291 0.374692768 0.115512557 0.918244779
1403636705063555584 5.870079041 -0.215201497 5.272164822 -0.056281220 0.373928428 0.114339761 0.918660104
1403636705113555456 5.899757385 -0.210344315 5.298436642 -0.051606905 0.374811649 0.111182593 0.918962121
1403636705163555584 5.928446770 -0.207339764 5.319590569 -0.043646570 0.375616193 0.106849283 0.919560015
1403636705213555456 5.955832005 -0.208102465 5.345414639 -0.035503823 0.377123415 0.101746775 0.919872284
1403636705263555584 5.993637085 -0.209661245 5.371721745 -0.028863646 0.377548605 0.099299334 0.920197606
1403636705313555456 6.023448944 -0.212798715 5.396239281 -0.024959395 0.377825886 0.096705869 0.920474112
1403636705363555584 6.056208134 -0.216797411 5.419318199 -0.021985937 0.377610326 0.096094064 0.920702457
1403636705413555456 6.083367825 -0.224069118 5.448344707 -0.023373678 0.378016114 0.096953772 0.920411587
1403636705463555584 6.113132000 -0.230809510 5.473841190 -0.025258459 0.377575397 0.098562978 0.920371771
1403636705513555456 6.144199848 -0.235506654 5.503003597 -0.028655769 0.377398133 0.100613303 0.920123041
1403636705563555584 6.177768707 -0.237718225 5.532207489 -0.031968284 0.376917362 0.101265274 0.920139492
1403636705613555456 6.205997467 -0.242366791 5.562248707 -0.033343233 0.376498491 0.102396280 0.920136988
1403636705663555584 6.240874767 -0.243923664 5.595593452 -0.034683082 0.376642227 0.103441514 0.919911742
1403636705713555456 6.267265320 -0.248008490 5.626220703 -0.032960694 0.377057642 0.102713220 0.919886470
1403636705763555584 6.290633678 -0.250942588 5.662746429 -0.029960746 0.377681077 0.102489494 0.919758260
1403636705813555456 6.323943138 -0.255476117 5.695584774 -0.025801307 0.377134055 0.104398251 0.919894099
1403636705863555584 6.356606483 -0.260449171 5.730364323 -0.021072913 0.376709133 0.105715662 0.920038223
1403636705913555456 6.389616013 -0.266020298 5.756281853 -0.015307379 0.375011683 0.108359724 0.920537889
1403636705963555584 6.417993546 -0.270610571 5.794949055 -0.009613354 0.373863637 0.111345425 0.920725644
1403636706013555456 6.447095871 -0.281979740 5.827898026 -0.004392357 0.371502787 0.116139255 0.921128690
1403636706063555584 6.477517128 -0.293327212 5.864031792 0.000104972 0.369141579 0.121723630 0.921367347
1403636706113555456 6.509955406 -0.305420041 5.898606300 0.004826419 0.367248446 0.125838727 0.921558380
1403636706163555584 6.538563251 -0.312870145 5.924592018 0.005756710 0.367814869 0.122469120 0.921781123
1403636706213555456 6.569881916 -0.317385972 5.955313683 0.004525285 0.369123548 0.116897188 0.921988249
1403636706263555584 6.601415157 -0.325672150 5.977835178 0.001112250 0.370064497 0.112731569 0.922140241
1403636706313555456 6.635187149 -0.326836646 6.010251999 -0.003237532 0.371824682 0.105889760 0.922238171
1403636706363555584 6.667601585 -0.328304172 6.035899639 -0.007509788 0.372292072 0.101681665 0.922498286
1403636706413555456 6.699860096 -0.326127172 6.069137096 -0.010750454 0.373185575 0.097729154 0.922532380
1403636706463555584 6.734464169 -0.325405121 6.103406429 -0.014710899 0.373508751 0.094875790 0.922644794
1403636706513555456 6.765801430 -0.324010491 6.135923386 -0.016987147 0.373883665 0.093220837 0.922622502
1403636706563555584 6.792212963 -0.329329669 6.158978939 -0.019660577 0.374322236 0.092922747 0.922421634
1403636706613555456 6.821876526 -0.332936704 6.184758663 -0.020743893 0.373940885 0.093249306 0.922519624
1403636706663555584 6.854036331 -0.338136315 6.228547096 -0.022019120 0.375138640 0.092585504 0.922070563
1403636706713555456 6.881138802 -0.346898794 6.249850750 -0.024562098 0.374864131 0.093930140 0.921981931
1403636706763555584 6.915864468 -0.347764850 6.267567635 -0.025915088 0.373030126 0.097713895 0.922295511
1403636706813555456 6.938221931 -0.366840601 6.306600094 -0.029781615 0.374763638 0.097216643 0.921528161
1403636706863555584 6.961426735 -0.379034877 6.339945316 -0.031439848 0.375680804 0.097317196 0.921088934
1403636706913555456 6.990676403 -0.387350082 6.368063927 -0.031050986 0.375957012 0.099795528 0.920724154
1403636706963555584 7.026185513 -0.401258707 6.389780998 -0.030949268 0.376010001 0.101109244 0.920562625
1403636707013555456 7.055532455 -0.419101119 6.430451870 -0.028416127 0.377499372 0.100582406 0.920092344
1403636707063555584 7.081107140 -0.432415009 6.461823940 -0.025818154 0.379683495 0.099794120 0.919355750
1403636707113555456 7.109896660 -0.448262930 6.501259327 -0.023613185 0.381102145 0.098793119 0.918936074
1403636707163555584 7.136603355 -0.462123513 6.533758640 -0.023255922 0.382707298 0.100356191 0.918108344
1403636707213555456 7.160957336 -0.476462483 6.567162037 -0.023351960 0.384641320 0.099712498 0.917367518
1403636707263555584 7.188402653 -0.492008448 6.600865841 -0.023505082 0.386077493 0.100686170 0.916653693
1403636707313555456 7.217236519 -0.512246728 6.632153511 -0.025207400 0.387333125 0.099875920 0.916167259
1403636707363555584 7.243274212 -0.532591343 6.661409378 -0.025764536 0.388126314 0.100565411 0.915740550
1403636707413555456 7.269391537 -0.556098580 6.703688145 -0.026613422 0.389320523 0.101336226 0.915124118
1403636707463555584 7.296575546 -0.580267429 6.733323574 -0.027457677 0.389457881 0.101768270 0.914992809
1403636707513555456 7.320381641 -0.607468963 6.774269104 -0.027365839 0.390167952 0.102907620 0.914565504
1403636707563555584 7.340556622 -0.629494429 6.806419373 -0.026097834 0.389960557 0.104225188 0.914541841
1403636707613555456 7.369163990 -0.661776781 6.839729309 -0.026579134 0.389167637 0.107800409 0.914451301
1403636707663555584 7.395141125 -0.689333916 6.877333164 -0.025286188 0.386721939 0.114407033 0.914722800
1403636707713555456 7.419193268 -0.710151434 6.925985336 -0.024241352 0.385919690 0.118354313 0.914587677
1403636707763555584 7.443574905 -0.730375409 6.965932369 -0.023614371 0.384145945 0.122032732 0.914867342
1403636707813555456 7.465083599 -0.749163628 7.013017654 -0.022224838 0.384682000 0.122817673 0.914571822
1403636707863555584 7.492008686 -0.766568184 7.046061039 -0.020471364 0.383026212 0.123486005 0.915217519
1403636707913555456 7.524440765 -0.780756235 7.083298206 -0.018815763 0.382030994 0.122929327 0.915743768
1403636707963555584 7.549242973 -0.789155841 7.134902954 -0.017136000 0.381957710 0.121507548 0.915997088
1403636708013555456 7.575231075 -0.792844534 7.184401512 -0.015478938 0.381724238 0.118770972 0.916482627
1403636708063555584 7.597393990 -0.795633316 7.224863052 -0.014649681 0.381780922 0.115470752 0.916894317
1403636708113555456 7.624874592 -0.799786925 7.272595406 -0.013350661 0.381427914 0.111635014 0.917535841
1403636708163555584 7.653911591 -0.806706071 7.317636490 -0.012764511 0.381406277 0.108980060 0.917872369
1403636708213555456 7.673584938 -0.800840735 7.365081787 -0.009988179 0.380885631 0.108327180 0.918200195
1403636708263555584 7.706103325 -0.806525588 7.412093163 -0.007457854 0.379305035 0.110242493 0.918650448
1403636708313555456 7.735670567 -0.809099913 7.465558052 -0.003316943 0.377470344 0.114395007 0.918922663
1403636708363555584 7.764938831 -0.808549702 7.504681110 0.002607236 0.374197036 0.121211380 0.919389784
1403636708413555456 7.785808563 -0.816908777 7.556878090 0.005982137 0.373424172 0.125732824 0.919080973
1403636708463555584 7.823287010 -0.823227346 7.589825630 0.009097424 0.371007353 0.130154252 0.919418693
1403636708513555456 7.853065014 -0.823565483 7.635020733 0.011668555 0.370704502 0.131242961 0.919357002
1403636708563555584 7.887236118 -0.831541300 7.667897224 0.012792519 0.370453477 0.129764676 0.919653058
1403636708613555456 7.910447598 -0.842194617 7.702295303 0.011866648 0.373641074 0.124807887 0.919061720
1403636708663555584 7.942593575 -0.844424844 7.734779835 0.009278199 0.376273543 0.118377455 0.918868303
1403636708713555456 7.979149818 -0.850599945 7.767245293 0.007281132 0.379694253 0.110298231 0.918484390
1403636708763555584 8.016758919 -0.849858880 7.804115295 0.004855845 0.382741123 0.103162296 0.918064892
1403636708813555456 8.047430992 -0.853047967 7.846436977 0.004177629 0.386510372 0.096328154 0.917231262
1403636708863555584 8.076939583 -0.852851570 7.878103733 0.002796142 0.388997048 0.093383878 0.916489482
1403636708913555456 8.099491119 -0.854768932 7.911330700 0.003499543 0.391917676 0.090421103 0.915539324
1403636708963555584 8.133502960 -0.858277380 7.938417435 0.004119067 0.393885463 0.089360110 0.914796174
1403636709013555456 8.164943695 -0.860122681 7.974149704 0.006847914 0.395805120 0.088214301 0.914062202
1403636709063555584 8.182819366 -0.865180373 7.999554157 0.007650126 0.398753971 0.085053779 0.913073182
1403636709113555456 8.199662209 -0.869893610 8.032482147 0.008984890 0.400897861 0.084832639 0.912142277
1403636709163555584 8.229368210 -0.881472766 8.056807518 0.007410283 0.402158380 0.085786536 0.911512196
1403636709213555456 8.247289658 -0.887401164 8.085881233 0.005489069 0.403149217 0.087506063 0.910924375
1403636709263555584 8.264844894 -0.899546325 8.114355087 0.001002500 0.403917044 0.087949529 0.910557449
1403636709313555456 8.287934303 -0.914008975 8.137011528 -0.002412452 0.403703123 0.090494782 0.910400271
1403636709363555584 8.303603172 -0.923704803 8.161702156 -0.005204733 0.403340667 0.091850065 0.910413504
1403636709413555456 8.320367813 -0.933242559 8.191060066 -0.007285158 0.404304117 0.091380790 0.910019040
1403636709463555584 8.324819565 -0.942731738 8.220106125 -0.007961935 0.404562593 0.091535799 0.909882903
1403636709513555456 8.340360641 -0.956040263 8.251399040 -0.010066575 0.404872239 0.091258973 0.909752131
1403636709563555584 8.357809067 -0.958067417 8.278584480 -0.010568182 0.403996527 0.091917172 0.910069406
1403636709613555456 8.365169525 -0.964996099 8.310900688 -0.012364921 0.404045463 0.092364244 0.909979820
1403636709663555584 8.371414185 -0.968606949 8.339676857 -0.013205218 0.403709084 0.092205681 0.910133362
1403636709713555456 8.384415627 -0.974863410 8.374260902 -0.014391106 0.402970403 0.091299258 0.910534024
1403636709763555584 8.393084526 -0.976245642 8.408448219 -0.013899378 0.401679695 0.092103966 0.911030769
1403636709813555456 8.398093224 -0.982114077 8.444907188 -0.014337965 0.401696682 0.090845980 0.911142826
1403636709863555584 8.408114433 -0.991504312 8.475595474 -0.013829176 0.400292695 0.092084892 0.911644042
1403636709913555456 8.415886879 -0.992825866 8.515744209 -0.013095379 0.400104403 0.090300925 0.911915958
1403636709963555584 8.426019669 -1.006427169 8.541193962 -0.012883934 0.398724109 0.090107232 0.912542462
1403636710013555456 8.426985741 -1.018122673 8.577231407 -0.012203266 0.397907257 0.090253741 0.912893832
1403636710063555584 8.431890488 -1.032048821 8.618079185 -0.011795566 0.397293925 0.089869857 0.913204134
1403636710113555456 8.435192108 -1.041304469 8.653854370 -0.010890036 0.396362066 0.088531449 0.913750887
1403636710163555584 8.436048508 -1.052905083 8.693998337 -0.010478731 0.395555019 0.087860160 0.914170146
1403636710213555456 8.435815811 -1.061782122 8.724124908 -0.009960896 0.394352108 0.087594099 0.914720953
1403636710263555584 8.430588722 -1.068802714 8.758708954 -0.009002140 0.392491758 0.088378541 0.915455282
1403636710313555456 8.433473587 -1.074557066 8.801215172 -0.005420589 0.388966948 0.093220681 0.916507065
1403636710363555584 8.430023193 -1.081868768 8.847520828 -0.002332593 0.384913117 0.099551909 0.917565167
1403636710413555456 8.431310654 -1.080941916 8.882214546 0.000844378 0.378845632 0.104562059 0.919533610
1403636710463555584 8.428311348 -1.082736254 8.922966003 0.002677075 0.372357428 0.109155282 0.921644092
1403636710513555456 8.420932770 -1.080030084 8.963170052 0.005176610 0.365489185 0.112529449 0.923974037
1403636710563555584 8.420866013 -1.084655285 8.996869087 0.005656227 0.358223408 0.113990836 0.926633716
1403636710613555456 8.420652390 -1.078471184 9.039896965 0.007084218 0.351941884 0.113517687 0.929085851
1403636710663555584 8.419105530 -1.075487375 9.072004318 0.007493532 0.344386399 0.111775555 0.932120144
1403636710713555456 8.419016838 -1.065214038 9.116078377 0.008197978 0.337861955 0.108121932 0.934928715
1403636710763555584 8.417675018 -1.060692549 9.153609276 0.008394523 0.330617577 0.104056641 0.937973201
1403636710813555456 8.416797638 -1.057940364 9.184365273 0.007237435 0.323769778 0.095831804 0.941242278
1403636710863555584 8.418476105 -1.058169842 9.215162277 0.004663932 0.316083848 0.087367706 0.944688380
1403636710913555456 8.412016869 -1.053753734 9.248634338 0.002639902 0.309184760 0.079167008 0.947697401
1403636710963555584 8.409615517 -1.058277726 9.276352882 0.000929323 0.302202642 0.071554460 0.950553894
1403636711013555456 8.407934189 -1.059463143 9.303800583 -0.002745920 0.296772718 0.062998898 0.952863872
1403636711063555584 8.408512115 -1.054109097 9.331033707 -0.002262159 0.290894985 0.058654729 0.954952657
1403636711113555456 8.407269478 -1.065371752 9.354682922 -0.004164327 0.286625296 0.053192027 0.956555903
1403636711163555584 8.403193474 -1.064831138 9.382366180 -0.003256110 0.283530533 0.049475349 0.957680523
1403636711213555456 8.394065857 -1.070225716 9.410382271 -0.002863490 0.281305939 0.046373822 0.958492696
1403636711263555584 8.393407822 -1.077829599 9.433332443 -0.002771631 0.278737485 0.045029193 0.959307075
1403636711313555456 8.382903099 -1.085356236 9.458927155 -0.000852563 0.276518643 0.046398971 0.959887385
1403636711363555584 8.374301910 -1.097671151 9.485570908 0.000587585 0.274965882 0.048150528 0.960247338
1403636711413555456 8.365185738 -1.105328918 9.511102676 0.006503207 0.273656756 0.049536489 0.960528910
1403636711463555584 8.355764389 -1.113069534 9.538450241 0.014501178 0.273231298 0.050127640 0.960531950
1403636711513555456 8.349689484 -1.125164270 9.554887772 0.021459268 0.272929966 0.049700227 0.960509539
1403636711563555584 8.337827682 -1.139803410 9.574946404 0.025377451 0.274775654 0.046934009 0.960026801
1403636711613555456 8.316986084 -1.148078442 9.603355408 0.028191619 0.277404815 0.044408254 0.959312081
1403636711663555584 8.302396774 -1.161286354 9.620140076 0.028567383 0.278978825 0.042727053 0.958920777
1403636711713555456 8.284816742 -1.163115382 9.639333725 0.027991353 0.280945301 0.040979747 0.958439827
1403636711763555584 8.265977859 -1.176931381 9.659064293 0.026111733 0.282259554 0.041761991 0.958072901
1403636711813555456 8.245371819 -1.188219547 9.663620949 0.023995072 0.282092482 0.044890359 0.958036005
1403636711863555584 8.223760605 -1.196173191 9.678153992 0.021496909 0.281309694 0.049696758 0.958088160
1403636711913555456 8.198919296 -1.204961419 9.688138962 0.018922752 0.279879630 0.057122149 0.958147407
1403636711963555584 8.172114372 -1.221831918 9.699650764 0.015592594 0.278763622 0.063983969 0.958099008
1403636712013555456 8.146474838 -1.227715015 9.713735580 0.015044264 0.277234584 0.071428552 0.958025396
1403636712063555584 8.117955208 -1.242251992 9.717931747 0.014004339 0.275883317 0.077701256 0.957943022
1403636712113555456 8.093728065 -1.254555225 9.725897789 0.014809346 0.274915993 0.080837876 0.957949460
1403636712163555584 8.070231438 -1.265012383 9.734045982 0.015981665 0.274197400 0.082246095 0.958016694
1403636712213555456 8.048132896 -1.277960777 9.733129501 0.014966759 0.272890806 0.077434532 0.958806813
1403636712263555584 8.022459984 -1.294935107 9.732978821 0.013208497 0.270644128 0.070232876 0.960023224
1403636712313555456 7.998011112 -1.307415724 9.736309052 0.013341671 0.266710907 0.062536366 0.961652994
1403636712363555584 7.970247269 -1.321551800 9.735413551 0.012650548 0.262169510 0.054029141 0.963425100
1403636712413555456 7.941662312 -1.329793692 9.733930588 0.013507024 0.257327884 0.047619127 0.965055645
1403636712463555584 7.913094044 -1.352683663 9.730236053 0.013726749 0.252724081 0.042632330 0.966501236
1403636712513555456 7.887897491 -1.374721527 9.720344543 0.013901482 0.246866658 0.038473278 0.968185604
1403636712563555584 7.867585659 -1.392623305 9.713994026 0.014681722 0.240986124 0.036202803 0.969742000
1403636712613555456 7.832455635 -1.411969185 9.715947151 0.017357629 0.236630082 0.034975298 0.970814943
1403636712663555584 7.799864769 -1.425715446 9.704228401 0.021759627 0.231211334 0.035060469 0.972028077
1403636712713555456 7.768750191 -1.436405897 9.702948570 0.025603436 0.227347076 0.035021834 0.972846985
1403636712763555584 7.739433765 -1.453107834 9.689264297 0.026317716 0.222910270 0.035141807 0.973849773
1403636712813555456 7.706560135 -1.459545612 9.679527283 0.026417645 0.219749972 0.035770249 0.974542201
1403636712863555584 7.674774170 -1.469271660 9.673496246 0.024014754 0.217502981 0.035971362 0.975100875
1403636712913555456 7.639943123 -1.476799011 9.663743019 0.021425577 0.215973705 0.036256354 0.975490570
1403636712963555584 7.606652260 -1.478704691 9.653141022 0.018193748 0.215114623 0.036148671 0.975749969
1403636713013555456 7.573168755 -1.481777906 9.639121056 0.016055033 0.215260252 0.034510426 0.975814700
1403636713063555584 7.538012505 -1.485371947 9.624392509 0.016459355 0.214685664 0.035338111 0.975904882
1403636713113555456 7.501507759 -1.490084648 9.610168457 0.017020920 0.213076591 0.037013154 0.976185799
1403636713163555584 7.462669373 -1.492324948 9.593995094 0.016499842 0.212102830 0.038049478 0.976366937
1403636713213555456 7.429606915 -1.500179291 9.574993134 0.014986507 0.211244196 0.039485633 0.976520479
1403636713263555584 7.392883301 -1.513578176 9.560297012 0.011896368 0.210841745 0.040454481 0.976610303
1403636713313555456 7.358552933 -1.519688845 9.535984039 0.011034057 0.210664243 0.040637545 0.976651132
1403636713363555584 7.322413921 -1.531259060 9.514297485 0.008805851 0.210693106 0.040929124 0.976655364
1403636713413555456 7.285257339 -1.540952206 9.494049072 0.009334272 0.210222647 0.043672312 0.976633012
1403636713463555584 7.252130508 -1.551590204 9.471136093 0.008912330 0.209765226 0.045233734 0.976664245
1403636713513555456 7.215744019 -1.568504572 9.442601204 0.008363806 0.209306449 0.047756162 0.976647437
1403636713563555584 7.180859566 -1.585520029 9.410480499 0.008279880 0.208441168 0.050228532 0.976709187
1403636713613555456 7.151735306 -1.596642971 9.385416031 0.007038490 0.207483977 0.054626398 0.976686656
1403636713663555584 7.107532501 -1.604095101 9.367785454 0.006046667 0.208197176 0.057734441 0.976362705
1403636713713555456 7.075883389 -1.609289050 9.340085983 0.006238400 0.207935721 0.061678708 0.976175964
1403636713763555584 7.040538311 -1.620737672 9.317045212 0.005031832 0.208016232 0.064866766 0.975959122
1403636713813555456 7.009891987 -1.631315470 9.287110329 0.003865523 0.207977295 0.066940747 0.975832701
1403636713863555584 6.976600647 -1.633038640 9.266431808 0.003898146 0.209268689 0.067091845 0.975546062
1403636713913555456 6.948510170 -1.638344169 9.240225792 0.002894990 0.210747749 0.065772161 0.975320995
1403636713963555584 6.917204857 -1.635167122 9.209241867 0.003055585 0.212399140 0.064473532 0.975048959
1403636714013555456 6.891345024 -1.643299103 9.185661316 0.000465369 0.214069664 0.063003212 0.974784374
1403636714063555584 6.860012054 -1.642891645 9.155979156 0.000041543 0.217062816 0.058033753 0.974431038
1403636714113555456 6.837225914 -1.637602329 9.134039879 -0.000170273 0.218285605 0.057692666 0.974178076
1403636714163555584 6.810492516 -1.633874416 9.108262062 -0.000548580 0.220258862 0.056412779 0.973808646
1403636714213555456 6.781748772 -1.628575444 9.083743095 0.001391892 0.221364707 0.056319419 0.973562419
1403636714263555584 6.757946968 -1.629095912 9.058119774 0.002366474 0.221598044 0.058870997 0.973356545
1403636714313555456 6.734915257 -1.619572282 9.033519745 0.003507467 0.221893236 0.061231699 0.973140121
1403636714363555584 6.710915565 -1.610295177 9.006011963 0.002902939 0.222030148 0.062597774 0.973024011
1403636714413555456 6.686962128 -1.600384951 8.979475975 -0.000789026 0.222857580 0.063319065 0.972792149
1403636714463555584 6.665753365 -1.590528965 8.951872826 -0.005344730 0.221787333 0.064160094 0.972967267
1403636714513555456 6.642903328 -1.589150429 8.923704147 -0.010941228 0.219169348 0.064148702 0.973514259
1403636714563555584 6.622861862 -1.580599189 8.887823105 -0.014937242 0.214054555 0.064589128 0.974569499
1403636714613555456 6.598643303 -1.565020323 8.868861198 -0.018123191 0.209038064 0.063538395 0.975672841
1403636714663555584 6.577596664 -1.554607749 8.846830368 -0.020645857 0.202850580 0.060505204 0.977120519
1403636714713555456 6.560222626 -1.544635534 8.825194359 -0.022943059 0.194392264 0.057439588 0.978971899
1403636714763555584 6.540351868 -1.531965256 8.798001289 -0.024110468 0.185123116 0.052599266 0.981010437
1403636714813555456 6.523793221 -1.529246688 8.775465965 -0.025233090 0.175275490 0.045645650 0.983136952
1403636714863555584 6.511708260 -1.526027441 8.746755600 -0.025258141 0.163782701 0.037830748 0.985447168
1403636714913555456 6.488152504 -1.525473237 8.727653503 -0.026148155 0.153291449 0.031380843 0.987336457
1403636714963555584 6.476775169 -1.523787498 8.695432663 -0.026742253 0.140509292 0.025810819 0.989381552
1403636715013555456 6.461031914 -1.526273012 8.675773621 -0.027496574 0.130021483 0.020633731 0.990915060
1403636715063555584 6.446689606 -1.537564516 8.649439812 -0.029091330 0.119751163 0.015245209 0.992260516
1403636715113555456 6.431557655 -1.541718602 8.629785538 -0.030337943 0.112177238 0.010321880 0.993171394
1403636715163555584 6.409333706 -1.548639297 8.619507790 -0.030949071 0.106338158 0.007596135 0.993819237
1403636715213555456 6.404036045 -1.558020353 8.594786644 -0.031009004 0.100168779 0.005504631 0.994471908
1403636715263555584 6.392049789 -1.561973810 8.581013680 -0.029547550 0.095398821 0.004256609 0.994991422
1403636715313555456 6.380970478 -1.573304534 8.554507256 -0.027810818 0.090653382 0.004441368 0.995484173
1403636715363555584 6.365768909 -1.578421116 8.545708656 -0.026084466 0.088018611 0.004088313 0.995768845
1403636715413555456 6.355588913 -1.585520029 8.532747269 -0.022737747 0.084207274 0.006071121 0.996170282
1403636715463555584 6.343035698 -1.588250160 8.521125793 -0.018956784 0.082323484 0.009062548 0.996384144
1403636715513555456 6.330368519 -1.590619326 8.509775162 -0.015251728 0.079684831 0.015246625 0.996586800
1403636715563555584 6.319952011 -1.591805339 8.496030807 -0.012215155 0.076956429 0.022927105 0.996695936
1403636715613555456 6.310664654 -1.592775464 8.487375259 -0.011845130 0.075946577 0.025706515 0.996710062
1403636715663555584 6.300302982 -1.585953593 8.481262207 -0.007424145 0.076837979 0.024745254 0.996708810
1403636715713555456 6.295843601 -1.583998680 8.470452309 -0.001454965 0.079024427 0.020416990 0.996662498
1403636715763555584 6.291344643 -1.579980850 8.461915970 0.003572003 0.081256852 0.014695408 0.996578455
1403636715813555456 6.287331581 -1.572652340 8.454188347 0.008454718 0.083767124 0.010969206 0.996389091
1403636715863555584 6.285029411 -1.569125652 8.442119598 0.012461379 0.085355811 0.007810348 0.996241987
1403636715913555456 6.279147625 -1.565829873 8.427913666 0.016753789 0.087858431 0.004336275 0.995982647
1403636715963555584 6.279860497 -1.562882662 8.410177231 0.019395469 0.089019321 0.004102705 0.995832562
1403636716013555456 6.266714573 -1.568094492 8.394464493 0.019984690 0.091196366 0.003454219 0.995626390
1403636716063555584 6.259820938 -1.565683007 8.377731323 0.019948225 0.092534050 0.004000272 0.995501637
1403636716113555456 6.262330055 -1.568755269 8.353037834 0.018387351 0.092213824 0.006223839 0.995549977
1403636716163555584 6.253375530 -1.573530674 8.335222244 0.013267457 0.093370073 0.008877770 0.995503485
1403636716213555456 6.248503685 -1.572968483 8.317570686 0.007100343 0.094070196 0.012372704 0.995463312
1403636716263555584 6.240291119 -1.571183801 8.297225952 0.003173300 0.096047185 0.012945517 0.995287538
1403636716313555456 6.236455917 -1.568105102 8.271967888 -0.000268246 0.097308457 0.014556722 0.995147765
1403636716363555584 6.228487968 -1.563241720 8.249709129 -0.002857092 0.098931529 0.015627537 0.994967401
1403636716413555456 6.219987869 -1.559559584 8.230920792 -0.003585167 0.100716263 0.016120026 0.994778097
1403636716463555584 6.221005917 -1.556019545 8.208441734 -0.004601795 0.101810932 0.016158724 0.994661868
1403636716513555456 6.212613583 -1.545199513 8.186225891 -0.003632492 0.103492521 0.016344875 0.994489312
1403636716563555584 6.208601475 -1.542784333 8.162875175 -0.003651341 0.104053698 0.014160685 0.994464159
1403636716613555456 6.210151196 -1.538465381 8.139183998 -0.004544192 0.102400966 0.012597342 0.994653046
1403636716663555584 6.196034431 -1.517394304 8.129741669 -0.003122485 0.100785017 0.010679948 0.994845986
1403636716713555456 6.200154305 -1.510924816 8.098972321 -0.003747248 0.095572263 0.008868896 0.995375931
1403636716763555584 6.198172092 -1.502468586 8.074685097 -0.003532843 0.089975849 0.007607013 0.995908618
1403636716813555456 6.194193363 -1.480692983 8.059694290 -0.002854335 0.082782947 0.005383711 0.996548951
1403636716863555584 6.187154770 -1.465752840 8.037838936 -0.003174200 0.075183451 0.003242804 0.997159362
1403636716913555456 6.177018166 -1.453294039 8.018512726 -0.003593130 0.065973975 0.000556192 0.997814715
1403636716963555584 6.175093174 -1.445193887 7.998570442 -0.005478397 0.055428267 -0.003865478 0.998440146
1403636717013555456 6.169356823 -1.436601162 7.975608826 -0.005448715 0.044176545 -0.007770622 0.998978674
1403636717063555584 6.162135124 -1.430100679 7.949873447 -0.006563930 0.033299364 -0.012259403 0.999348640
1403636717113555456 6.153982162 -1.420358896 7.925658703 -0.006570414 0.022614241 -0.016162423 0.999592006
1403636717163555584 6.149260998 -1.413501024 7.901078224 -0.006684300 0.013940676 -0.021004425 0.999659836
1403636717213555456 6.147188663 -1.412478566 7.875124931 -0.007313906 0.006159695 -0.024832025 0.999645889
1403636717263555584 6.143751144 -1.405555010 7.851341724 -0.007384480 0.000209255 -0.030309526 0.999513268
1403636717313555456 6.141065121 -1.404911876 7.820623398 -0.007888375 -0.003706752 -0.036259148 0.999304414
1403636717363555584 6.135749817 -1.399477363 7.796146870 -0.007303709 -0.005607376 -0.044358246 0.998973250
1403636717413555456 6.129399300 -1.392573357 7.774493694 -0.006426405 -0.007280773 -0.050705034 0.998666465
1403636717463555584 6.122229576 -1.390337706 7.746722221 -0.006385356 -0.008646380 -0.055381529 0.998407423
1403636717513555456 6.115382671 -1.385880113 7.721335411 -0.006748714 -0.010446847 -0.056547273 0.998322487
1403636717563555584 6.105366707 -1.381843448 7.697717667 -0.006642284 -0.012215855 -0.054966576 0.998391390
1403636717613555456 6.101651192 -1.370071650 7.676124096 -0.006983540 -0.014914856 -0.051640503 0.998529911
1403636717663555584 6.087278843 -1.361730337 7.651744843 -0.006566321 -0.015118878 -0.049486287 0.998638749
1403636717713555456 6.074938774 -1.351269841 7.628238201 -0.005770793 -0.015475917 -0.048275724 0.998697460
1403636717763555584 6.067079067 -1.341492295 7.607155800 -0.006822299 -0.015684661 -0.051375516 0.998532951
1403636717813555456 6.049939156 -1.323454976 7.584668636 -0.006709123 -0.016990896 -0.053116977 0.998421192
1403636717863555584 6.033498287 -1.307243824 7.558159828 -0.006990238 -0.019753492 -0.055637319 0.998231113
1403636717913555456 6.020856380 -1.297215462 7.535482407 -0.007296665 -0.024912572 -0.059367057 0.997898638
1403636717963555584 6.004786968 -1.282009721 7.515974998 -0.006949512 -0.030401103 -0.063168727 0.997515500
1403636718013555456 5.989087582 -1.281000495 7.485620499 -0.007485153 -0.038592998 -0.065753214 0.997061193
1403636718063555584 5.962962627 -1.271702290 7.459072113 -0.007858803 -0.046323076 -0.067890622 0.996585846
1403636718113555456 5.941867828 -1.268577933 7.432197571 -0.007860533 -0.057190694 -0.067239597 0.996065438
1403636718163555584 5.922746181 -1.264564753 7.400394440 -0.008770317 -0.068275347 -0.066309161 0.995421827
1403636718213555456 5.894475937 -1.255402923 7.372124672 -0.008984857 -0.077433825 -0.066321336 0.994748592
1403636718263555584 5.868111134 -1.250016212 7.344077587 -0.010265126 -0.086321130 -0.065700293 0.994045675
1403636718313555456 5.852302074 -1.239701986 7.320713043 -0.011562143 -0.094916180 -0.064522468 0.993324757
1403636718363555584 5.825617313 -1.223815441 7.304887295 -0.011882728 -0.102547519 -0.064202659 0.992582917
1403636718413555456 5.799372673 -1.214052439 7.273075581 -0.013473405 -0.110799648 -0.064537965 0.991653562
1403636718463555584 5.781815052 -1.201807499 7.250312805 -0.014572194 -0.120581672 -0.063263915 0.990578294
1403636718513555456 5.753921509 -1.181687593 7.227823734 -0.014465065 -0.128806010 -0.064231202 0.989481747
1403636718563555584 5.724296570 -1.162671566 7.205317020 -0.014817135 -0.136740178 -0.063330896 0.988469422
1403636718613555456 5.701884270 -1.145891190 7.187550545 -0.016069634 -0.144158512 -0.061871290 0.987487733
1403636718663555584 5.679378510 -1.128918171 7.168375492 -0.017805155 -0.152188316 -0.058047265 0.986484766
1403636718713555456 5.659111977 -1.108149648 7.146658897 -0.019551124 -0.158616334 -0.055496056 0.985585511
1403636718763555584 5.635640144 -1.087947845 7.125422478 -0.019310707 -0.162839010 -0.055946887 0.984875858
1403636718813555456 5.621452332 -1.063783050 7.105080605 -0.019167041 -0.165858284 -0.059461281 0.984168708
1403636718863555584 5.599540234 -1.041048646 7.088173389 -0.017793957 -0.166785881 -0.066845052 0.983563721
1403636718913555456 5.582158566 -1.024734259 7.068205833 -0.016661100 -0.167533562 -0.071787305 0.983108103
1403636718963555584 5.564370155 -1.005817533 7.057379723 -0.014532543 -0.168103606 -0.076646380 0.982677639
1403636719013555456 5.545012474 -0.994246006 7.039562225 -0.013710953 -0.168458387 -0.080471411 0.982322812
1403636719063555584 5.524022579 -0.983605146 7.022285461 -0.011643347 -0.168749928 -0.082181364 0.982157886
1403636719113555456 5.509021759 -0.973417163 7.005660057 -0.008596036 -0.169166297 -0.083079480 0.982042074
1403636719163555584 5.489239216 -0.964611232 6.984435081 -0.005243095 -0.169689521 -0.082999721 0.981982172
1403636719213555456 5.473549366 -0.960489273 6.963150978 -0.002105332 -0.170076847 -0.081837356 0.982024491
1403636719263555584 5.453594208 -0.948359966 6.943729401 0.001431685 -0.169723660 -0.080955081 0.982159913
1403636719313555456 5.435329914 -0.938000083 6.917553425 0.003564392 -0.170015439 -0.077727132 0.982364774
1403636719363555584 5.411873341 -0.927254081 6.900749207 0.006049668 -0.169443771 -0.077103890 0.982500494
1403636719413555456 5.399230003 -0.916077912 6.875844955 0.007097466 -0.169488281 -0.075208075 0.982632756
1403636719463555584 5.383879185 -0.904686630 6.861901760 0.007310793 -0.169604808 -0.073430844 0.982745469
1403636719513555456 5.367686749 -0.884562433 6.843932629 0.007640179 -0.169012234 -0.072388843 0.982922316
1403636719563555584 5.348848343 -0.870515108 6.816785812 0.004587086 -0.167738244 -0.072030060 0.983185887
1403636719613555456 5.333799362 -0.854144931 6.797114849 0.001537973 -0.167311758 -0.069917753 0.983420491
1403636719663555584 5.322880268 -0.838478923 6.774220467 -0.002154502 -0.165860683 -0.070310414 0.983637154
1403636719713555456 5.309257507 -0.822347879 6.752649307 -0.005074348 -0.164430901 -0.070017837 0.983887315
1403636719763555584 5.294615746 -0.813293040 6.728272438 -0.008193346 -0.162986830 -0.069730043 0.984126985
1403636719813555456 5.281610012 -0.803351581 6.704717636 -0.010238344 -0.161484718 -0.068868071 0.984416127
1403636719863555584 5.266005039 -0.792338967 6.682128429 -0.010263155 -0.159696475 -0.068344086 0.984744012
1403636719913555456 5.252683640 -0.784796953 6.659075260 -0.011267675 -0.158279121 -0.067065515 0.985049725
1403636719963555584 5.239040375 -0.781891465 6.633378029 -0.013273960 -0.157183379 -0.066797435 0.985218406
1403636720013555456 5.235409737 -0.771991909 6.613079071 -0.013061497 -0.156327695 -0.067076303 0.985338390
1403636720063555584 5.223373413 -0.762507081 6.591203690 -0.013594425 -0.155787066 -0.066827357 0.985433757
1403636720113555456 5.208858013 -0.748528600 6.569628716 -0.013609603 -0.154708102 -0.066644393 0.985615909
1403636720163555584 5.202105522 -0.741240799 6.546359539 -0.015151007 -0.154600531 -0.067400232 0.985558867
1403636720213555456 5.193431854 -0.728417635 6.523190498 -0.015204757 -0.154970899 -0.066520937 0.985559642
1403636720263555584 5.183509350 -0.719500661 6.503476143 -0.015758323 -0.155066639 -0.065916978 0.985576451
1403636720313555456 5.175247192 -0.705997944 6.481051922 -0.015856216 -0.155370235 -0.064610578 0.985613585
1403636720363555584 5.161973000 -0.687573195 6.462735176 -0.015528736 -0.155343667 -0.064368390 0.985638857
1403636720413555456 5.153116703 -0.671644270 6.447624207 -0.015353085 -0.156100139 -0.064264424 0.985528827
1403636720463555584 5.146675587 -0.655265450 6.428686142 -0.015827084 -0.157128319 -0.063839145 0.985385597
1403636720513555456 5.140307426 -0.641171455 6.410166740 -0.016526274 -0.157940924 -0.063749373 0.985249996
1403636720563555584 5.130370617 -0.627732873 6.393456936 -0.016277831 -0.158366814 -0.063566953 0.985197544
1403636720613555456 5.123248100 -0.620288849 6.376065254 -0.017121740 -0.158635646 -0.065029502 0.985044539
1403636720663555584 5.117930889 -0.612115085 6.356418610 -0.017160734 -0.159688234 -0.064326331 0.984919965
1403636720713555456 5.111267090 -0.608938038 6.338810921 -0.016127372 -0.159679681 -0.064164542 0.984949350
1403636720763555584 5.100429535 -0.606883764 6.316637993 -0.017017743 -0.157953903 -0.063102633 0.985281169
1403636720813555456 5.100696564 -0.601468444 6.306905746 -0.016796691 -0.155260265 -0.062957458 0.985722303
1403636720863555584 5.099468708 -0.598926306 6.286253929 -0.016793985 -0.150274888 -0.062711328 0.986510396
1403636720913555456 5.094038010 -0.597168922 6.270215034 -0.017155372 -0.144137442 -0.060579892 0.987552643
1403636720963555584 5.094792366 -0.593200266 6.256851196 -0.016207922 -0.138277769 -0.058145713 0.988552332
1403636721013555456 5.095753193 -0.586159050 6.245778561 -0.014888042 -0.132964015 -0.054425992 0.989513397
1403636721063555584 5.095776558 -0.575323582 6.238147736 -0.012602304 -0.127356872 -0.050699253 0.990480185
1403636721113555456 5.088459015 -0.566819668 6.222987652 -0.011635817 -0.119345628 -0.048109442 0.991618216
1403636721163555584 5.088161469 -0.558418274 6.213066101 -0.009246677 -0.110706553 -0.045285992 0.992777765
1403636721213555456 5.087460518 -0.549095154 6.198115349 -0.007758309 -0.102554947 -0.041863374 0.993815780
1403636721263555584 5.086215019 -0.540688455 6.190283298 -0.005244200 -0.095334359 -0.038970139 0.994668365
1403636721313555456 5.089282036 -0.534998178 6.177498817 -0.005031318 -0.088885345 -0.037174046 0.995335221
1403636721363555584 5.095283031 -0.530348837 6.160026550 -0.004649445 -0.083017565 -0.035627726 0.995900154
1403636721413555456 5.091860771 -0.528215289 6.142735958 -0.003680804 -0.076887935 -0.035324216 0.996406972
1403636721463555584 5.093194962 -0.525880218 6.127406597 -0.004154140 -0.072281860 -0.033760015 0.996804059
1403636721513555456 5.094033241 -0.524522424 6.113471985 -0.004765385 -0.066757321 -0.033743162 0.997187138
1403636721563555584 5.095374107 -0.524849236 6.095330238 -0.005718106 -0.060777746 -0.032696608 0.997599304
1403636721613555456 5.099461079 -0.520544052 6.076129436 -0.006825191 -0.054849446 -0.032629255 0.997938037
1403636721663555584 5.099798203 -0.519187033 6.059802055 -0.008171665 -0.049719531 -0.032424983 0.998203278
1403636721713555456 5.110490322 -0.507553339 6.055617809 -0.006724211 -0.046648055 -0.032616872 0.998356104
1403636721763555584 5.115915298 -0.496834040 6.042915821 -0.006733361 -0.043016858 -0.033335995 0.998495340
1403636721813555456 5.116841316 -0.489797354 6.025577068 -0.006679574 -0.040558591 -0.033172265 0.998604000
1403636721863555584 5.116571426 -0.477947712 6.011297703 -0.005657529 -0.039113674 -0.032246239 0.998698294
1403636721913555456 5.122542858 -0.472511411 5.998887062 -0.006049462 -0.038522188 -0.032888703 0.998698056
1403636721963555584 5.128004074 -0.460664600 5.985835075 -0.005734997 -0.037849400 -0.035290275 0.998643637
1403636722013555456 5.129397392 -0.449711293 5.967700481 -0.005500572 -0.036559459 -0.038592480 0.998570859
1403636722063555584 5.132582664 -0.437290162 5.947106838 -0.004962081 -0.035764303 -0.042364817 0.998449564
1403636722113555456 5.134399891 -0.429198086 5.933453560 -0.004826531 -0.036203496 -0.043015115 0.998406589
1403636722163555584 5.131307602 -0.423724949 5.916185379 -0.005656672 -0.037292093 -0.042456739 0.998386025
1403636722213555456 5.130339622 -0.421840668 5.898561001 -0.006173598 -0.038259309 -0.041011296 0.998406827
1403636722263555584 5.130650997 -0.419194847 5.879687309 -0.007013909 -0.039474867 -0.039952651 0.998396873
1403636722313555456 5.136324406 -0.414629698 5.858105183 -0.006431633 -0.041334569 -0.038213499 0.998393595
1403636722363555584 5.134969234 -0.413561434 5.840023041 -0.007430935 -0.041853882 -0.037698314 0.998384655
1403636722413555456 5.136810780 -0.401926994 5.831135273 -0.007035734 -0.040814806 -0.037622496 0.998433352
1403636722463555584 5.136157036 -0.401977658 5.808356285 -0.007081079 -0.038358092 -0.036846258 0.998559356
1403636722513555456 5.139032364 -0.395486742 5.788715839 -0.006916896 -0.036474209 -0.035595242 0.998676479
1403636722563555584 5.137966156 -0.387652248 5.772015095 -0.007043848 -0.034434799 -0.034815162 0.998775482
1403636722613555456 5.136341572 -0.377121210 5.756690979 -0.007046312 -0.031526159 -0.035857901 0.998834670
1403636722663555584 5.139075756 -0.366306543 5.739202023 -0.007240912 -0.030021770 -0.035810526 0.998881280
1403636722713555456 5.138455391 -0.356779218 5.722441673 -0.006856911 -0.028404150 -0.036539454 0.998904943
1403636722763555584 5.133754730 -0.346059024 5.706793785 -0.007276522 -0.026451077 -0.037782133 0.998909354
1403636722813555456 5.136281967 -0.335430026 5.691487789 -0.007858880 -0.025547823 -0.038342539 0.998907089
1403636722863555584 5.133347988 -0.327529728 5.671492577 -0.007655973 -0.024549212 -0.039103772 0.998904228
1403636722913555456 5.133660793 -0.319522917 5.658140659 -0.007873095 -0.024330541 -0.037916597 0.998953640
1403636722963555584 5.132450104 -0.317914575 5.637971878 -0.008579579 -0.025020393 -0.036321141 0.998990059
1403636723013555456 5.127048492 -0.317149222 5.623251915 -0.008201121 -0.025326805 -0.034858394 0.999037623
1403636723063555584 5.122399330 -0.322131097 5.597802162 -0.008057315 -0.026209639 -0.032177798 0.999105990
1403636723113555456 5.120584965 -0.322735667 5.576056480 -0.007997926 -0.026586983 -0.031342819 0.999122977
1403636723163555584 5.117596149 -0.322345257 5.559214592 -0.007845409 -0.026689120 -0.031306729 0.999122620
1403636723213555456 5.113682747 -0.321151227 5.540025711 -0.008066729 -0.026798442 -0.031039316 0.999126256
1403636723263555584 5.110750675 -0.318871766 5.521945000 -0.008848431 -0.026075667 -0.031733613 0.999116957
1403636723313555456 5.102465153 -0.315448463 5.501156807 -0.008609520 -0.024473090 -0.034221470 0.999077499
1403636723363555584 5.099387646 -0.307924360 5.481611729 -0.008027402 -0.022333777 -0.034480691 0.999123514
1403636723413555456 5.096221924 -0.306872904 5.464962482 -0.007930784 -0.018223399 -0.035315439 0.999178588
1403636723463555584 5.096654415 -0.293027282 5.448233604 -0.004638227 -0.013159237 -0.036784343 0.999225855
1403636723513555456 5.087579727 -0.292310387 5.427493095 -0.001335248 -0.007231869 -0.034816124 0.999366641
1403636723563555584 5.083613396 -0.287847817 5.410717964 0.004760387 -0.002576396 -0.030846808 0.999509454
1403636723613555456 5.083537579 -0.280571043 5.393425465 0.011880358 0.001457360 -0.026542990 0.999576032
1403636723663555584 5.080081463 -0.279008150 5.374762058 0.012996889 0.005492204 -0.023527842 0.999623597
1403636723713555456 5.068623543 -0.281581551 5.350794792 0.008600626 0.009649694 -0.022617374 0.999660611
1403636723763555584 5.059931278 -0.282191515 5.321808815 0.003980638 0.013749789 -0.020923838 0.999678612
1403636723813555456 5.054271698 -0.277073473 5.302684307 -0.000642269 0.016109554 -0.018257692 0.999703288
1403636723863555584 5.051370144 -0.274643719 5.280739784 -0.004199218 0.018468611 -0.016732277 0.999680579
1403636723913555456 5.050410748 -0.266083837 5.261017799 -0.007122917 0.020239752 -0.014386828 0.999666274
1403636723963555584 5.039702415 -0.262146562 5.239981651 -0.011539775 0.022693748 -0.012707965 0.999595106
1403636724013555456 5.033168316 -0.256660223 5.217127323 -0.016018447 0.025920050 -0.011821170 0.999465764
1403636724063555584 5.026821613 -0.252258211 5.193355083 -0.020060414 0.030710377 -0.010375816 0.999273121
1403636724113555456 5.024369240 -0.238250315 5.173480511 -0.023199968 0.036188334 -0.008973098 0.999035358
1403636724163555584 5.015748501 -0.227379560 5.159321308 -0.023438318 0.043406058 -0.007554092 0.998753965
1403636724213555456 5.007615566 -0.223684341 5.139466763 -0.025385840 0.051250614 -0.004340597 0.998353660
1403636724263555584 5.004952908 -0.208659858 5.124221325 -0.024678066 0.059719380 -0.001540712 0.997908890
1403636724313555456 5.004549503 -0.194359303 5.107857227 -0.023065284 0.068864964 0.000580677 0.997359157
1403636724363555584 4.998881817 -0.189975619 5.090648651 -0.021614149 0.078399196 0.002781987 0.996683836
1403636724413555456 4.993550301 -0.175764427 5.087342262 -0.018475536 0.088239722 0.004262716 0.995918810
1403636724463555584 4.990995407 -0.163225010 5.069601059 -0.015594045 0.096068531 0.007446414 0.995224655
1403636724513555456 4.989495277 -0.158295825 5.055156708 -0.012703040 0.103069380 0.008015350 0.994560719
1403636724563555584 4.980074883 -0.150446445 5.036673546 -0.010026015 0.108908124 0.009629503 0.993954599
1403636724613555456 4.972672462 -0.156469941 5.027329445 -0.010388069 0.114284694 0.010506457 0.993338168
1403636724663555584 4.974030495 -0.154688373 5.008462429 -0.009335963 0.117244288 0.011636809 0.992991030
1403636724713555456 4.965469360 -0.154246911 4.992228031 -0.009075344 0.119950958 0.012974056 0.992653549
1403636724763555584 4.961856842 -0.156476483 4.976210594 -0.009459550 0.121749535 0.013930324 0.992417991
1403636724813555456 4.955143452 -0.160257757 4.956655502 -0.010140292 0.122832932 0.014555696 0.992268801
1403636724863555584 4.942817688 -0.169265032 4.944226265 -0.011358986 0.123799235 0.015560443 0.992120206
1403636724913555456 4.936427593 -0.184759408 4.920183659 -0.012537962 0.122767501 0.017663160 0.992199063
1403636724963555584 4.927462101 -0.195687398 4.903563023 -0.013227414 0.121487878 0.020025996 0.992302716
1403636725013555456 4.917963982 -0.205367967 4.887034893 -0.012833013 0.119869128 0.022717411 0.992446780
1403636725063555584 4.911357403 -0.217087820 4.867403984 -0.011772656 0.118240170 0.024517683 0.992612481
1403636725113555456 4.911719322 -0.237608984 4.842891693 -0.012441634 0.116001450 0.026641278 0.992813706
1403636725163555584 4.899024010 -0.251795292 4.824296951 -0.013100282 0.115217328 0.027836718 0.992863774
1403636725213555456 4.888389111 -0.270749956 4.805273533 -0.013197385 0.115210131 0.026960617 0.992887497
1403636725263555584 4.883390903 -0.286378562 4.791890144 -0.013867589 0.114369154 0.027238410 0.992968023
1403636725313555456 4.878673553 -0.297654182 4.772431374 -0.013972574 0.114844553 0.024852207 0.992974222
1403636725363555584 4.877386570 -0.307456970 4.752408981 -0.013886199 0.114462614 0.023910869 0.993042648
1403636725413555456 4.873874664 -0.317110300 4.740352631 -0.013529471 0.114919290 0.022089586 0.993037045
1403636725463555584 4.866169930 -0.335210383 4.712655067 -0.014004423 0.115321524 0.021124003 0.993004799
1403636725513555456 4.861809731 -0.342798799 4.706700325 -0.014079169 0.115908474 0.019501556 0.992968619
1403636725563555584 4.856935978 -0.351282954 4.694863796 -0.014917433 0.116630003 0.018761031 0.992886186
1403636725613555456 4.852701187 -0.356913686 4.684422970 -0.014984357 0.117183737 0.016970234 0.992852151
1403636725663555584 4.848923683 -0.363514364 4.669942379 -0.013572822 0.117454164 0.016855905 0.992842436
1403636725713555456 4.846496582 -0.366609931 4.656589031 -0.012731355 0.117260076 0.017627079 0.992863119
1403636725763555584 4.848705292 -0.366944790 4.646558762 -0.013050822 0.116739511 0.017595015 0.992920935
1403636725813555456 4.841419220 -0.368753612 4.632327080 -0.012737996 0.117021300 0.017415343 0.992894948
1403636725863555584 4.837649822 -0.366414845 4.625156403 -0.014014083 0.116392456 0.018366653 0.992934585
1403636725913555456 4.836747646 -0.365283817 4.620733738 -0.013666207 0.115225516 0.020113971 0.993041635
1403636725963555584 4.830496311 -0.365318775 4.605772495 -0.014441736 0.114752874 0.020446932 0.993078589
1403636726013555456 4.828452110 -0.362132251 4.593305588 -0.013225740 0.113874413 0.021283403 0.993179083
1403636726063555584 4.821053505 -0.356880844 4.588076115 -0.012953274 0.113818169 0.019939356 0.993217051
1403636726113555456 4.817409515 -0.351806760 4.589203835 -0.012919737 0.114099614 0.018565014 0.993211865
1403636726163555584 4.818243027 -0.339368939 4.584600449 -0.010672991 0.113822415 0.017565399 0.993288517
1403636726213555456 4.810727119 -0.335193992 4.580220222 -0.010091675 0.113674164 0.016727766 0.993325949
1403636726263555584 4.808818817 -0.331661582 4.570399284 -0.010261002 0.113275275 0.015454888 0.993390441
1403636726313555456 4.805754662 -0.324627489 4.566694260 -0.009805525 0.112512499 0.015391446 0.993482709
1403636726363555584 4.804815769 -0.317466468 4.560087204 -0.008418300 0.112060241 0.014495132 0.993560016
1403636726413555456 4.806138992 -0.311472416 4.558142185 -0.007476217 0.110999025 0.013885550 0.993695378
1403636726463555584 4.803439140 -0.314781874 4.552144527 -0.007231237 0.110268414 0.014857882 0.993764460
1403636726513555456 4.796258926 -0.313330799 4.537098885 -0.006146403 0.108498387 0.016576838 0.993939400
1403636726563555584 4.798737526 -0.316042811 4.527996063 -0.004398183 0.105082780 0.023003366 0.994187653
1403636726613555456 4.788516045 -0.323547512 4.523049831 -0.003117431 0.102080487 0.030983632 0.994288623
1403636726663555584 4.787499428 -0.333740503 4.510851860 -0.000304605 0.098944508 0.038066812 0.994364500
1403636726713555456 4.787642002 -0.332667440 4.498867989 0.000290896 0.098404229 0.039373063 0.994367301
1403636726763555584 4.786816597 -0.338906527 4.491758347 0.001140696 0.099492624 0.035332907 0.994410157
1403636726813555456 4.787086487 -0.353587508 4.471735954 0.000374678 0.100810088 0.029108871 0.994479716
1403636726863555584 4.788182259 -0.359473825 4.460152626 0.000846648 0.100997582 0.023037048 0.994619548
1403636726913555456 4.782106876 -0.376623601 4.450847149 0.000089934 0.100955874 0.017955450 0.994728863
1403636726963555584 4.785549641 -0.385550231 4.427471161 0.000352561 0.099853337 0.014468886 0.994896889
1403636727013555456 4.793009758 -0.401027024 4.414615631 0.000433620 0.098517366 0.012559346 0.995055974
1403636727063555584 4.791293144 -0.420226425 4.395710945 -0.000011592 0.098268643 0.009694297 0.995112717
1403636727113555456 4.800721169 -0.431702465 4.379226208 -0.000283406 0.097284280 0.007164637 0.995230854
1403636727163555584 4.798513412 -0.447702795 4.360430717 -0.001692169 0.097787678 0.004168536 0.995197117
1403636727213555456 4.796046734 -0.462038279 4.338824749 -0.002606389 0.098001741 0.001115535 0.995182216
1403636727263555584 4.797254562 -0.470423788 4.328890324 -0.003360334 0.098388970 -0.001393910 0.995141387
1403636727313555456 4.802570820 -0.468568057 4.314340591 -0.003266301 0.098754637 -0.004310298 0.995097101
1403636727363555584 4.793267250 -0.482858092 4.298932076 -0.005851973 0.099635527 -0.005941664 0.994989038
1403636727413555456 4.801997185 -0.490521491 4.278129578 -0.005862873 0.099091135 -0.006160732 0.995042026
1403636727463555584 4.804758549 -0.492405623 4.262882233 -0.005751488 0.099312074 -0.006860158 0.995016098
1403636727513555456 4.800394535 -0.506387532 4.242733002 -0.004462727 0.098499350 -0.005119587 0.995113909
1403636727563555584 4.792858124 -0.512544513 4.230469227 -0.002944125 0.097702704 -0.001716580 0.995209873
1403636727613555456 4.788022041 -0.521504164 4.215024948 -0.001388922 0.097194232 -0.000497430 0.995264351
1403636727663555584 4.785263538 -0.527470291 4.193642616 -0.000769866 0.096474007 0.001544690 0.995334029
1403636727713555456 4.780597687 -0.533685446 4.182645321 -0.001959971 0.096507438 0.000942437 0.995329916
1403636727763555584 4.773222923 -0.552607477 4.162055016 -0.003337133 0.096867703 -0.000209802 0.995291650
1403636727813555456 4.776445389 -0.572430551 4.133580685 -0.004496338 0.096607819 -0.001382444 0.995311439
1403636727863555584 4.763835907 -0.587029636 4.116570950 -0.005421057 0.098750554 -0.006126071 0.995078564
1403636727913555456 4.757711887 -0.596454084 4.092224121 -0.005268705 0.100448363 -0.010446265 0.994873464
1403636727963555584 4.745627403 -0.613408327 4.073136806 -0.005888817 0.101176418 -0.012364934 0.994774222
1403636728013555456 4.733538151 -0.618068874 4.062990189 -0.005412507 0.101006299 -0.010418095 0.994816482
1403636728063555584 4.720123291 -0.631044984 4.044213295 -0.005633214 0.100662909 -0.009003639 0.994863868
1403636728113555456 4.710318089 -0.641258836 4.032069206 -0.004102428 0.099388681 -0.005596937 0.995024502
1403636728163555584 4.707074165 -0.641950309 4.013010502 -0.002314943 0.098725595 -0.003842783 0.995104551
1403636728213555456 4.686100006 -0.660484254 3.981439590 -0.001871845 0.098453827 -0.001822177 0.995138168
1403636728263555584 4.673632622 -0.665927649 3.972327471 -0.001406610 0.098249644 -0.000718493 0.995160520
1403636728313555456 4.658822536 -0.667220891 3.950061321 -0.001374876 0.097942784 0.001302113 0.995190203
1403636728363555584 4.645101547 -0.666680157 3.938326836 -0.001754977 0.098058105 0.001059223 0.995178580
1403636728413555456 4.630243301 -0.666849732 3.920457840 -0.001901977 0.096779585 0.005004035 0.995291412
1403636728463555584 4.614479065 -0.666947961 3.896038532 -0.000890123 0.094943322 0.011834736 0.995411932
1403636728513555456 4.592221737 -0.665124953 3.887475491 -0.000954707 0.092809953 0.018404452 0.995513260
1403636728563555584 4.584225655 -0.662556648 3.876043081 -0.001476389 0.090808310 0.022379149 0.995615780
1403636728613555456 4.568396091 -0.656078517 3.855540514 -0.000621518 0.088727914 0.023801871 0.995771289
1403636728663555584 4.554010868 -0.651295722 3.834511995 -0.001590902 0.086874731 0.019047268 0.996035874
1403636728713555456 4.537522316 -0.649355710 3.827873707 -0.002036575 0.084507644 0.012379899 0.996343851
1403636728763555584 4.534001827 -0.643720031 3.800772190 -0.002388352 0.078995384 0.006398492 0.996851563
1403636728813555456 4.522205830 -0.640325189 3.781975031 -0.002650998 0.072920255 -0.000004733 0.997334242
1403636728863555584 4.507979393 -0.633053660 3.779003859 -0.002387452 0.067224160 -0.005895100 0.997717619
1403636728913555456 4.488073826 -0.639216065 3.751135588 -0.001721287 0.061760962 -0.010633915 0.998032868
1403636728963555584 4.472651958 -0.641073287 3.727709532 -0.000871877 0.056288954 -0.013653859 0.998320758
1403636729013555456 4.462800503 -0.641607583 3.710439920 0.000442714 0.051264267 -0.016281689 0.998552322
1403636729063555584 4.455448151 -0.639497340 3.688657999 0.002037499 0.046411712 -0.018935818 0.998740852
1403636729113555456 4.432024956 -0.639959514 3.674715042 0.002876767 0.042864725 -0.020504039 0.998866320
1403636729163555584 4.417609692 -0.639186263 3.655723572 0.001904751 0.040287543 -0.022150420 0.998940766
1403636729213555456 4.410405636 -0.628640294 3.631941319 0.000511597 0.037101097 -0.022026710 0.999068618
1403636729263555584 4.383744717 -0.623403013 3.611477137 -0.001025007 0.035180625 -0.021166211 0.999156296
1403636729313555456 4.379475117 -0.611747563 3.586367130 -0.001079638 0.033199646 -0.021006683 0.999227345
1403636729363555584 4.363174438 -0.605509400 3.568028688 -0.000948327 0.032023326 -0.020592896 0.999274492
1403636729413555456 4.353083134 -0.592282236 3.547154427 -0.000015737 0.031099891 -0.021070546 0.999294162
1403636729463555584 4.346050739 -0.583796084 3.528665304 0.000288369 0.029910283 -0.020494200 0.999342442
1403636729513555456 4.326190948 -0.578614116 3.500370502 -0.000033928 0.029645475 -0.020694721 0.999346197
1403636729563555584 4.305768967 -0.570983350 3.477384806 -0.000429810 0.029306239 -0.020471429 0.999360740
1403636729613555456 4.292068958 -0.570219636 3.454281807 -0.001256333 0.028934710 -0.020518493 0.999369860
1403636729663555584 4.277204514 -0.563066304 3.426834822 -0.001578084 0.028662892 -0.019885642 0.999390125
1403636729713555456 4.260232449 -0.568692923 3.400544882 -0.001828806 0.028318070 -0.019465752 0.999407768
1403636729763555584 4.241130829 -0.567141354 3.379150867 -0.003612104 0.028985636 -0.019717297 0.999378860
1403636729813555456 4.223392963 -0.561476529 3.348384380 -0.005247266 0.029434439 -0.018587410 0.999380112
1403636729863555584 4.198962688 -0.561202884 3.330016375 -0.008549150 0.030795811 -0.019843301 0.999292135
1403636729913555456 4.183063030 -0.554746628 3.300577164 -0.010152130 0.030275542 -0.017632382 0.999334514
1403636729963555584 4.168164730 -0.545619547 3.277110577 -0.011174003 0.030491691 -0.017845949 0.999313235
1403636730013555456 4.154967308 -0.540244222 3.252497196 -0.012938316 0.030221736 -0.016508218 0.999323130
1403636730063555584 4.127961636 -0.533071458 3.229632139 -0.014112608 0.030540759 -0.017026853 0.999288857
1403636730113555456 4.112261772 -0.524447083 3.210045338 -0.014557249 0.030178031 -0.016820308 0.999296963
1403636730163555584 4.101971626 -0.516534269 3.179905415 -0.014505023 0.029434545 -0.015709620 0.999338031
1403636730213555456 4.085032940 -0.508034527 3.165877819 -0.015728045 0.029413356 -0.016944028 0.999299943
1403636730263555584 4.073751926 -0.507533073 3.142017126 -0.016789060 0.028669268 -0.017594170 0.999293089
1403636730313555456 4.049213886 -0.490495265 3.125098228 -0.015694423 0.028578592 -0.015832072 0.999342918
1403636730363555584 4.036778450 -0.479712963 3.100478649 -0.016392339 0.027716765 -0.015353531 0.999363482
1403636730413555456 4.025635242 -0.466229647 3.074825764 -0.017252376 0.027578464 -0.016093733 0.999341130
1403636730463555584 4.013390064 -0.454364896 3.054652691 -0.020927675 0.026722752 -0.015238628 0.999307632
1403636730513555456 3.994282246 -0.442608297 3.036915779 -0.024842916 0.027239736 -0.016413243 0.999185383
1403636730563555584 3.978376865 -0.431935281 3.020039558 -0.028600827 0.026782839 -0.015906299 0.999105453
1403636730613555456 3.961254358 -0.432181895 3.001498222 -0.031911068 0.026508924 -0.015655885 0.999016464
1403636730663555584 3.950541258 -0.423826814 2.985637188 -0.033030506 0.025649408 -0.013922075 0.999028146
1403636730713555456 3.931958914 -0.416862845 2.970491886 -0.033066895 0.025658075 -0.013627148 0.999030828
1403636730763555584 3.913570642 -0.427870095 2.952818394 -0.035335533 0.026443323 -0.014942267 0.998913825
1403636730813555456 3.902531862 -0.435320467 2.933022261 -0.035703767 0.025552055 -0.015322491 0.998918176
1403636730863555584 3.888410091 -0.441583306 2.917157650 -0.036345273 0.024963144 -0.013364828 0.998938084
1403636730913555456 3.863637686 -0.451955587 2.908221483 -0.037582230 0.024768831 -0.010362982 0.998932779
1403636730963555584 3.849350691 -0.465098500 2.890469074 -0.036497209 0.023185644 -0.005259911 0.999050915
1403636731013555456 3.834813118 -0.459673762 2.881685495 -0.034560129 0.021871230 0.000938047 0.999162853
1403636731063555584 3.830210924 -0.463735282 2.865739584 -0.028548790 0.019452028 0.008388244 0.999367893
1403636731113555456 3.817240477 -0.468445778 2.859801531 -0.021766886 0.018699801 0.012225001 0.999513447
1403636731163555584 3.806240320 -0.480619192 2.855556488 -0.017542383 0.018558953 0.013529281 0.999582350
1403636731213555456 3.793821335 -0.480773985 2.850572586 -0.013478687 0.020040296 0.012093856 0.999635160
1403636731263555584 3.783879519 -0.482411832 2.847551346 -0.010306630 0.021794330 0.007857688 0.999678433
1403636731313555456 3.783736706 -0.472712964 2.833556414 -0.007461877 0.023409162 0.003233657 0.999692917
1403636731363555584 3.772986412 -0.480335116 2.830931425 -0.007541835 0.025792936 -0.001707181 0.999637365
1403636731413555456 3.772117853 -0.472073197 2.829520702 -0.008048516 0.027294932 -0.006043813 0.999576747
1403636731463555584 3.760456562 -0.470200568 2.821328640 -0.007617729 0.028533664 -0.007710335 0.999534070
1403636731513555456 3.765127420 -0.466189355 2.814729691 -0.008379620 0.027344398 -0.005878080 0.999573648
1403636731563555584 3.754733562 -0.461388260 2.813546181 -0.009005148 0.026251344 -0.002210206 0.999612331
1403636731613555456 3.756700516 -0.456019998 2.802905321 -0.008808978 0.024980679 0.001177854 0.999648392
1403636731663555584 3.753531694 -0.446638882 2.805126667 -0.008762302 0.024066275 0.003698803 0.999665141
1403636731713555456 3.754836082 -0.439671516 2.795877457 -0.008832572 0.024138557 0.003199614 0.999664485
1403636731763555584 3.752511740 -0.437540114 2.790948629 -0.009903229 0.025346568 -0.000393829 0.999629557
1403636731813555456 3.754398584 -0.425731868 2.788782597 -0.009865563 0.025861533 -0.002599460 0.999613464
1403636731863555584 3.751608133 -0.415449858 2.785187006 -0.009976428 0.026747415 -0.005352112 0.999578118
1403636731913555456 3.757392645 -0.399869114 2.776890755 -0.009527540 0.026499381 -0.006501627 0.999582291
1403636731963555584 3.761846542 -0.383798808 2.776829958 -0.008257018 0.025919111 -0.006789363 0.999606907
1403636732013555456 3.755164862 -0.377315670 2.775332451 -0.008659034 0.026514221 -0.008019186 0.999578774
1403636732063555584 3.754664421 -0.364804476 2.768568039 -0.007317997 0.026755933 -0.009292676 0.999572039
1403636732113555456 3.759396076 -0.349420100 2.768280745 -0.007462006 0.026232343 -0.008122721 0.999595046
1403636732163555584 3.757075548 -0.324070275 2.774174213 -0.006256918 0.026217109 -0.009097896 0.999595284
1403636732213555456 3.766029596 -0.299732506 2.766351700 -0.003836028 0.025626613 -0.008744813 0.999625981
1403636732263555584 3.772261620 -0.294729650 2.755659103 -0.003767202 0.025598036 -0.011606662 0.999597847
1403636732313555456 3.768755674 -0.281834185 2.759490252 -0.002923768 0.025207387 -0.010726744 0.999620438
1403636732363555584 3.772787333 -0.273718864 2.749857187 -0.003612290 0.025755811 -0.013355655 0.999572515
1403636732413555456 3.768589020 -0.265795976 2.747558594 -0.002206905 0.027921168 -0.018148804 0.999442935
1403636732463555584 3.775975466 -0.256322920 2.740607023 0.000541014 0.029789256 -0.025270423 0.999236584
1403636732513555456 3.782282352 -0.249031544 2.725075006 0.003435325 0.032004919 -0.033682901 0.998914063
1403636732563555584 3.789039373 -0.237609655 2.713008881 0.007171591 0.033415385 -0.039107881 0.998650372
1403636732613555456 3.779170990 -0.236139953 2.706520081 0.009947076 0.035528574 -0.044754103 0.998316526
1403636732663555584 3.773871899 -0.238222510 2.691869020 0.012014551 0.035034291 -0.044413533 0.998326421
1403636732713555456 3.770407677 -0.235663146 2.675690889 0.014117476 0.033296321 -0.040340044 0.998531282
1403636732763555584 3.770306110 -0.237309784 2.660890341 0.014098220 0.030738911 -0.035925146 0.998782158
1403636732813555456 3.755230427 -0.234955013 2.650117874 0.015122376 0.029150093 -0.030923231 0.998982131
1403636732863555584 3.744232178 -0.238673478 2.632737398 0.014948220 0.028588627 -0.029212382 0.999052465
1403636732913555456 3.737694979 -0.234456360 2.611616850 0.014113564 0.027550681 -0.027782489 0.999134541
1403636732963555584 3.727207422 -0.235321149 2.586304188 0.011399729 0.027137047 -0.027438750 0.999190032
1403636733013555456 3.710639000 -0.219384313 2.577813864 0.009705572 0.027153216 -0.026420727 0.999234915
1403636733063555584 3.705019951 -0.219406307 2.554088831 0.006471370 0.026534544 -0.027353629 0.999252617
1403636733113555456 3.692526579 -0.218660295 2.520687580 0.001986992 0.026653806 -0.027248954 0.999271333
1403636733163555584 3.683942556 -0.213909760 2.502660990 0.001927772 0.027213408 -0.029479848 0.999193013
1403636733213555456 3.674312115 -0.205641866 2.481284618 0.000947824 0.026782598 -0.029510515 0.999205172
1403636733263555584 3.665712595 -0.194949746 2.451249838 0.001105864 0.026358007 -0.029530391 0.999215662
1403636733313555456 3.638144255 -0.204230115 2.427348614 -0.000352689 0.026462562 -0.028899677 0.999231935
1403636733363555584 3.622045755 -0.209932581 2.400733232 -0.002728652 0.025269412 -0.027740447 0.999292016
1403636733413555456 3.616086006 -0.209206209 2.362110138 -0.004930445 0.023239452 -0.025459077 0.999393523
1403636733463555584 3.601381302 -0.214757860 2.331549644 -0.006673628 0.022551751 -0.022897353 0.999461174
1403636733513555456 3.588941097 -0.215486869 2.309564590 -0.008511889 0.021923220 -0.022401348 0.999472439
1403636733563555584 3.568944216 -0.231594071 2.278543234 -0.011156078 0.022045122 -0.021974666 0.999453187
1403636733613555456 3.547861099 -0.225594997 2.263556004 -0.011884341 0.022064179 -0.022727000 0.999427497
1403636733663555584 3.536653757 -0.228892833 2.229980230 -0.013233757 0.020954121 -0.021036526 0.999471486
1403636733713555456 3.525666714 -0.226684719 2.202738047 -0.014056319 0.020572180 -0.020896273 0.999471128
1403636733763555584 3.510939837 -0.229013950 2.178765774 -0.014519561 0.020754250 -0.021903364 0.999439180
1403636733813555456 3.489634514 -0.221118242 2.155119181 -0.016216911 0.020588882 -0.021298863 0.999429584
1403636733863555584 3.472826958 -0.223183960 2.123553276 -0.017520957 0.020872418 -0.021852532 0.999389708
1403636733913555456 3.454281569 -0.224093556 2.103238344 -0.017033262 0.021548346 -0.023790918 0.999339581
1403636733963555584 3.435766697 -0.218079522 2.077761412 -0.014893619 0.022796327 -0.027271930 0.999257088
1403636734013555456 3.423310995 -0.203999251 2.059728384 -0.010838281 0.022820719 -0.028285377 0.999280572
1403636734063555584 3.408025026 -0.200671732 2.033291817 -0.008620985 0.023165448 -0.028771263 0.999280393
1403636734113555456 3.395717859 -0.191320002 2.008839846 -0.006202247 0.023086179 -0.026900969 0.999352217
1403636734163555584 3.375050783 -0.179626077 1.990224719 -0.005227942 0.023416713 -0.026240842 0.999367714
1403636734213555456 3.349405766 -0.192015648 1.963882804 -0.006223154 0.023294596 -0.025358109 0.999387622
1403636734263555584 3.338367939 -0.189410150 1.939408183 -0.005805776 0.021906560 -0.024500255 0.999442935
1403636734313555456 3.322439432 -0.183437109 1.908584356 -0.006645597 0.020892849 -0.022492500 0.999506593
1403636734363555584 3.308045149 -0.179934591 1.885570407 -0.007881837 0.019724056 -0.021801351 0.999536633
1403636734413555456 3.286519289 -0.179718286 1.860064983 -0.009225124 0.019089673 -0.019563248 0.999583781
1403636734463555584 3.263270855 -0.188560843 1.838322997 -0.011689506 0.018818378 -0.020325176 0.999547958
1403636734513555456 3.240273237 -0.187975243 1.811061978 -0.012988146 0.018348280 -0.019279672 0.999561369
1403636734563555584 3.225453615 -0.192162335 1.786461353 -0.015584121 0.017603906 -0.019654278 0.999530375
1403636734613555456 3.207955599 -0.184032783 1.756244540 -0.016944699 0.016740389 -0.018943220 0.999536812
1403636734663555584 3.193159103 -0.182661548 1.736298561 -0.018733669 0.016457668 -0.019346645 0.999501824
1403636734713555456 3.174553394 -0.185156733 1.713343263 -0.019980757 0.016335992 -0.020803396 0.999450386
1403636734763555584 3.161084414 -0.172983885 1.689274192 -0.019377828 0.015681559 -0.021529213 0.999457419
1403636734813555456 3.139058113 -0.175073788 1.668745399 -0.021145426 0.015394561 -0.021968143 0.999416471
1403636734863555584 3.117064714 -0.162794292 1.653429031 -0.020924717 0.015081993 -0.021924261 0.999426842
1403636734913555456 3.103193998 -0.157023877 1.631524324 -0.021301147 0.014111005 -0.021715520 0.999437630
1403636734963555584 3.088983536 -0.147133633 1.616052628 -0.021068670 0.013543616 -0.021127965 0.999463022
1403636735013555456 3.076401949 -0.128594995 1.599377751 -0.020221492 0.013313713 -0.021870986 0.999467611
1403636735063555584 3.065555811 -0.120237164 1.579937816 -0.019708853 0.012377396 -0.020937867 0.999509871
1403636735113555456 3.049392223 -0.108154662 1.556820750 -0.019513926 0.012333794 -0.020185675 0.999529719
1403636735163555584 3.030345678 -0.096904248 1.541607976 -0.019425163 0.012213152 -0.018868443 0.999558628
1403636735213555456 3.007252932 -0.093230151 1.526645541 -0.020590171 0.012675986 -0.018003711 0.999545515
1403636735263555584 2.999519110 -0.085850611 1.515654325 -0.021718970 0.012252629 -0.016391285 0.999554634
1403636735313555456 2.980218887 -0.082357571 1.492525458 -0.023155417 0.012930732 -0.014925737 0.999536812
1403636735363555584 2.974860668 -0.082287312 1.478469253 -0.023939377 0.012879544 -0.012990823 0.999546051
1403636735413555456 2.953861237 -0.092622377 1.464281678 -0.023263896 0.014336111 -0.013591784 0.999534190
1403636735463555584 2.936523438 -0.093653083 1.451822639 -0.021850713 0.015992977 -0.011593709 0.999566078
1403636735513555456 2.926487446 -0.095996350 1.439350963 -0.020377703 0.017564896 -0.011742458 0.999569058
1403636735563555584 2.911377430 -0.111527674 1.424081683 -0.019146554 0.019760462 -0.011985093 0.999549568
1403636735613555456 2.891210556 -0.119773120 1.412406445 -0.017975675 0.022017766 -0.012994451 0.999511480
1403636735663555584 2.875893831 -0.130983502 1.405460477 -0.018247234 0.024166200 -0.013811602 0.999445975
1403636735713555456 2.873504639 -0.131227851 1.378923655 -0.018006438 0.024463292 -0.011626729 0.999470949
1403636735763555584 2.856673956 -0.141354740 1.379063487 -0.018610248 0.026427722 -0.012863286 0.999394715
1403636735813555456 2.847650290 -0.145571113 1.356005788 -0.017900229 0.026646674 -0.011006267 0.999424040
1403636735863555584 2.837771416 -0.154837176 1.334166408 -0.017796576 0.027326202 -0.012011407 0.999395967
1403636735913555456 2.832724094 -0.157747656 1.335918069 -0.017051417 0.027311265 -0.010853660 0.999422610
1403636735963555584 2.818516254 -0.152341574 1.330806494 -0.016482111 0.027906233 -0.011855175 0.999404371
1403636736013555456 2.801870584 -0.161241904 1.328882694 -0.016172536 0.026962632 -0.014470284 0.999400854
1403636736063555584 2.792134047 -0.159075916 1.324823976 -0.014849932 0.024032276 -0.015229678 0.999484897
1403636736113555456 2.773917675 -0.170181006 1.312627912 -0.013187898 0.019606741 -0.016753897 0.999580383
1403636736163555584 2.755501270 -0.187362537 1.299114108 -0.011599636 0.014007984 -0.018408382 0.999665141
1403636736213555456 2.755247116 -0.193380669 1.296042204 -0.009993386 0.007054843 -0.020721205 0.999710441
1403636736263555584 2.740333319 -0.189765021 1.283408523 -0.008367552 0.001253164 -0.023005743 0.999699533
1403636736313555456 2.729763746 -0.211405233 1.274150968 -0.008699912 -0.004022978 -0.026424902 0.999604821
1403636736363555584 2.728044510 -0.209490344 1.258790493 -0.007352572 -0.009186205 -0.028299710 0.999530196
1403636736413555456 2.718342543 -0.219505563 1.248897672 -0.007768967 -0.012804382 -0.030399360 0.999425590
1403636736463555584 2.696465015 -0.212136194 1.248568773 -0.006447726 -0.014068964 -0.034645170 0.999279797
1403636736513555456 2.690472603 -0.213760197 1.240771651 -0.005333399 -0.016005896 -0.039548915 0.999075234
1403636736563555584 2.682919979 -0.218370542 1.231033444 -0.004737182 -0.017166967 -0.044262838 0.998861194
1403636736613555456 2.670652628 -0.222959012 1.219722748 -0.004400713 -0.017902775 -0.048676115 0.998644471
1403636736663555584 2.666312933 -0.222359076 1.206754565 -0.003525169 -0.019539248 -0.050262868 0.998538673
1403636736713555456 2.646961689 -0.226352081 1.196480751 -0.002992081 -0.019523710 -0.051368687 0.998484433
1403636736763555584 2.630656242 -0.221665710 1.190769315 -0.003686607 -0.020043816 -0.052090585 0.998434365
1403636736813555456 2.615486622 -0.210533127 1.190106392 -0.001978410 -0.021142337 -0.053225484 0.998356700
1403636736863555584 2.605111361 -0.203830883 1.173260450 -0.001656259 -0.022273012 -0.052056480 0.998394370
1403636736913555456 2.583890200 -0.198947310 1.172864795 -0.002348173 -0.022833640 -0.052689143 0.998347104
1403636736963555584 2.566735506 -0.201511696 1.164809823 -0.003158206 -0.024618817 -0.051414326 0.998368919
1403636737013555456 2.551547527 -0.191281796 1.153658152 -0.003198503 -0.027096786 -0.047813240 0.998483539
1403636737063555584 2.539567709 -0.184226617 1.139180541 -0.003134419 -0.029588012 -0.045161773 0.998536527
1403636737113555456 2.533854485 -0.179904655 1.130572557 -0.002922944 -0.033762731 -0.041187488 0.998576581
1403636737163555584 2.507961750 -0.174372807 1.119577885 -0.003525007 -0.034616999 -0.040903565 0.998557031
1403636737213555456 2.470190763 -0.167696118 1.124348640 -0.003928536 -0.035115853 -0.039945852 0.998576880
1403636737263555584 2.464525223 -0.154332593 1.107447624 -0.004470911 -0.037820969 -0.037285812 0.998578668
1403636737313555456 2.444099903 -0.138224393 1.107614160 -0.005972214 -0.039376158 -0.037724178 0.998494208
1403636737363555584 2.439976692 -0.130131304 1.091963172 -0.008224789 -0.041382782 -0.037499476 0.998405516
1403636737413555456 2.421423674 -0.119822033 1.077204943 -0.010170531 -0.042279258 -0.038277037 0.998320520
1403636737463555584 2.397674084 -0.113148592 1.074588776 -0.012364522 -0.043056317 -0.038042333 0.998271525
1403636737513555456 2.373965740 -0.119030088 1.066823602 -0.015026312 -0.043119691 -0.040289246 0.998144090
1403636737563555584 2.358759880 -0.115812220 1.050978065 -0.015881926 -0.044435333 -0.038520388 0.998142958
1403636737613555456 2.345148325 -0.114594586 1.043745756 -0.017214501 -0.045921851 -0.037197508 0.998103797
1403636737663555584 2.333339691 -0.104769319 1.033143044 -0.018007899 -0.048158541 -0.033571318 0.998112917
1403636737713555456 2.302661419 -0.121790744 1.027242541 -0.020821745 -0.048188288 -0.030819459 0.998145521
1403636737763555584 2.304634094 -0.127368987 0.998629212 -0.021840967 -0.050049879 -0.028352411 0.998105288
1403636737813555456 2.291351795 -0.123821050 0.987291157 -0.021580463 -0.051092714 -0.024724642 0.998154521
1403636737863555584 2.273838043 -0.133224145 0.974942148 -0.021792825 -0.051008973 -0.023379028 0.998186648
1403636737913555456 2.258443356 -0.145229012 0.969361901 -0.022144129 -0.050835535 -0.022936562 0.998197973
1403636737963555584 2.251549006 -0.157199696 0.955650687 -0.021537455 -0.050896488 -0.021920864 0.998231053
1403636738013555456 2.244791985 -0.170763642 0.948597431 -0.021026229 -0.050446123 -0.022363177 0.998254955
1403636738063555584 2.230698347 -0.194277883 0.937533319 -0.022079231 -0.048868403 -0.023297537 0.998289287
1403636738113555456 2.230130434 -0.209914282 0.924109221 -0.020675203 -0.047798734 -0.026194902 0.998299360
1403636738163555584 2.206852913 -0.229651421 0.916431189 -0.019687019 -0.045548972 -0.027317343 0.998394430
1403636738213555456 2.211354733 -0.235060304 0.905741155 -0.017480182 -0.044968773 -0.028376326 0.998432279
1403636738263555584 2.204987049 -0.244042695 0.900376439 -0.017019680 -0.044515412 -0.027660783 0.998480618
1403636738313555456 2.191331387 -0.263095081 0.899995983 -0.017599944 -0.042903949 -0.029174415 0.998498023
1403636738363555584 2.194506645 -0.272528857 0.891214788 -0.017966384 -0.042492509 -0.028442698 0.998530209
1403636738413555456 2.184296370 -0.278794616 0.891387165 -0.018088572 -0.041386344 -0.028170699 0.998582184
1403636738463555584 2.184525728 -0.289665461 0.883784652 -0.018901307 -0.039912574 -0.028514186 0.998617351
1403636738513555456 2.173604965 -0.289286494 0.886966109 -0.019428650 -0.036157906 -0.026162259 0.998814642
1403636738563555584 2.173126698 -0.296312064 0.882754505 -0.021357700 -0.031467192 -0.024260992 0.998982012
1403636738613555456 2.164554596 -0.297104359 0.886512160 -0.022816267 -0.024781521 -0.021175558 0.999208152
1403636738663555584 2.161716700 -0.302909553 0.887949884 -0.023542082 -0.017257443 -0.017938163 0.999412894
1403636738713555456 2.171373367 -0.303697199 0.886987269 -0.022826634 -0.009675600 -0.013778033 0.999597669
1403636738763555584 2.161916971 -0.302428365 0.896060348 -0.019795930 0.000554311 -0.008918924 0.999764085
1403636738813555456 2.162957907 -0.299238473 0.901194453 -0.016868278 0.010569394 -0.002421443 0.999798954
1403636738863555584 2.164876938 -0.300333768 0.903487742 -0.013744250 0.021574864 0.003578314 0.999666333
1403636738913555456 2.164350748 -0.294586331 0.916798472 -0.011693604 0.032898150 0.009414352 0.999345958
1403636738963555584 2.159535646 -0.289671034 0.924069405 -0.010050111 0.045234710 0.017153472 0.998778522
1403636739013555456 2.157840729 -0.289358675 0.939391136 -0.008794672 0.057814676 0.024321476 0.997992277
1403636739063555584 2.172700167 -0.278752863 0.933576941 -0.007996765 0.070111983 0.032218628 0.996986628
1403636739113555456 2.185249567 -0.265152395 0.945729971 -0.006899050 0.084163971 0.036410324 0.995762587
1403636739163555584 2.181599140 -0.258938670 0.959179342 -0.007661414 0.100164801 0.037621677 0.994229794
1403636739213555456 2.197034836 -0.246924639 0.953325689 -0.007093756 0.115200423 0.038983945 0.992551684
1403636739263555584 2.211701393 -0.234294072 0.962663651 -0.007220560 0.131036237 0.039762389 0.990553558
1403636739313555456 2.222836018 -0.225658178 0.969397366 -0.007274069 0.147002131 0.039274581 0.988329411
1403636739363555584 2.222592831 -0.214532286 0.980559587 -0.008051232 0.163779691 0.037654098 0.985745192
1403636739413555456 2.249484777 -0.185347497 0.983965933 -0.007169660 0.177205488 0.039208993 0.983366370
1403636739463555584 2.251854897 -0.183439076 0.995180964 -0.007764743 0.191461459 0.040412333 0.980637074
1403636739513555456 2.274260283 -0.179827407 0.980418682 -0.008393722 0.203217924 0.044205301 0.978099108
1403636739563555584 2.297090530 -0.162038133 0.995097876 -0.006131893 0.212778509 0.049585931 0.975822210
1403636739613555456 2.305984974 -0.163286507 0.994928896 -0.005978052 0.221295878 0.054873355 0.973643303
1403636739663555584 2.323923588 -0.174303144 0.978724599 -0.007602088 0.227750689 0.057168763 0.972010076
1403636739713555456 2.323997974 -0.182522357 0.985274196 -0.007442960 0.234142184 0.059142973 0.970373213
1403636739763555584 2.331979752 -0.176131010 0.990353703 -0.006367991 0.237809747 0.063866034 0.969188869
1403636739813555456 2.348429680 -0.167248011 0.986321747 -0.005543518 0.240156412 0.066470765 0.968439877
1403636739863555584 2.358031988 -0.168846756 0.984023690 -0.006300308 0.242284402 0.067976095 0.967800498
1403636739913555456 2.356986761 -0.172060430 0.989309251 -0.006776427 0.244358733 0.068307981 0.967252254
1403636739963555584 2.376479387 -0.161816806 0.992552936 -0.006496343 0.244965538 0.068316191 0.967100084
1403636740013555456 2.384392262 -0.166763365 0.988886774 -0.007978261 0.245415837 0.066547856 0.967098117
1403636740063555584 2.394909859 -0.145193219 0.994458318 -0.008262194 0.245666295 0.065465726 0.967106044
1403636740113555456 2.408869267 -0.129804462 0.997187018 -0.008067140 0.245807767 0.062320542 0.967279494
1403636740163555584 2.418897629 -0.114392661 1.017719984 -0.008567845 0.246464446 0.058272764 0.967360437
1403636740213555456 2.431466579 -0.099384062 1.015066147 -0.008357314 0.246518523 0.053988770 0.967597008
1403636740263555584 2.442706347 -0.081174687 1.017528772 -0.008801711 0.246174961 0.050388046 0.967874706
1403636740313555456 2.459404945 -0.084401369 1.009266138 -0.008040736 0.244275287 0.049755216 0.968395233
1403636740363555584 2.462127209 -0.070496954 1.013457537 -0.007048708 0.243075371 0.051389974 0.968619466
1403636740413555456 2.457952976 -0.050289378 1.015510917 -0.005247405 0.241410717 0.054406799 0.968882442
1403636740463555584 2.481271505 -0.042136483 1.015992522 -0.005715064 0.238753051 0.056478951 0.969419658
1403636740513555456 2.488108635 -0.027278647 1.029459476 -0.003117563 0.236623332 0.058438201 0.969837427
1403636740563555584 2.510025978 -0.010090567 1.039963961 -0.002317272 0.234901339 0.059095975 0.970218360
1403636740613555456 2.508498669 0.002694711 1.030572414 -0.002185242 0.234093562 0.057782304 0.970493019
1403636740663555584 2.513141870 0.025227644 1.037699103 -0.002367992 0.232537031 0.058956999 0.970796049
1403636740713555456 2.525562525 0.048409015 1.047098637 -0.003992321 0.231309935 0.061025631 0.970956028
1403636740763555584 2.540332556 0.058135077 1.046121001 -0.006867232 0.230078250 0.060633216 0.971257150
1403636740813555456 2.542719841 0.072614580 1.055692196 -0.006807336 0.229820669 0.060835350 0.971305907
1403636740863555584 2.554324865 0.081570417 1.048180342 -0.006068863 0.228854313 0.061263334 0.971512020
1403636740913555456 2.561673880 0.100723989 1.053676486 -0.004967149 0.229100153 0.057612944 0.971683681
1403636740963555584 2.560352564 0.114877753 1.060650587 -0.004068796 0.231050655 0.051893611 0.971548319
1403636741013555456 2.581607103 0.127179846 1.052900672 -0.004487492 0.232117191 0.044974521 0.971637189
1403636741063555584 2.582386494 0.152262628 1.053692818 -0.003694032 0.235416248 0.037798647 0.971152306
1403636741113555456 2.597934246 0.170363724 1.062091947 -0.002574822 0.238040671 0.036450576 0.970567524
1403636741163555584 2.596573114 0.182593778 1.062420964 -0.001038249 0.241872221 0.037897881 0.969567180
1403636741213555456 2.598875999 0.201877162 1.060506582 0.001008789 0.244824603 0.042717118 0.968625367
1403636741263555584 2.604607821 0.223806798 1.061209679 0.002480756 0.246463493 0.049867995 0.967865050
1403636741313555456 2.614706993 0.250822216 1.071245670 0.002795690 0.247381821 0.056285385 0.967277825
1403636741363555584 2.615314722 0.283920407 1.070006847 -0.000209803 0.248472646 0.061639402 0.966675699
1403636741413555456 2.617687225 0.307557404 1.066144109 -0.004051456 0.250059634 0.065816402 0.965982378
1403636741463555584 2.632172108 0.346146166 1.072240829 -0.007268095 0.250847399 0.069500126 0.965501189
1403636741513555456 2.631398201 0.361882329 1.078034639 -0.014584970 0.252290726 0.072368711 0.964831293
1403636741563555584 2.632014036 0.382669181 1.068279505 -0.017539004 0.251548618 0.077892363 0.964545727
1403636741613555456 2.629293919 0.388045728 1.069412708 -0.022888573 0.253913641 0.076432958 0.963930488
1403636741663555584 2.634322405 0.399024546 1.062022209 -0.024863809 0.254014909 0.076626688 0.963839471
1403636741713555456 2.638256073 0.426994234 1.076473832 -0.023919834 0.255050361 0.075595468 0.963671386
1403636741763555584 2.648721695 0.431912899 1.064559102 -0.022067079 0.255003989 0.074212819 0.963835299
1403636741813555456 2.643399715 0.437760472 1.074228406 -0.020365318 0.256317556 0.069829583 0.963851869
1403636741863555584 2.656835556 0.465659618 1.074981809 -0.016762992 0.255741239 0.066564821 0.964305222
1403636741913555456 2.672228098 0.476053119 1.079279661 -0.016142873 0.255647600 0.062864035 0.964588940
1403636741963555584 2.664110661 0.478625655 1.068726063 -0.016373370 0.256411433 0.056343518 0.964785218
1403636742013555456 2.669118881 0.494993567 1.083572507 -0.018609690 0.256582767 0.051508550 0.964969337
1403636742063555584 2.680483580 0.517073274 1.081285477 -0.020945834 0.254917502 0.051279917 0.965374887
1403636742113555456 2.685010672 0.533900023 1.094824672 -0.025458306 0.252862930 0.053038839 0.965711713
1403636742163555584 2.688505411 0.552457929 1.093377113 -0.028032245 0.250147134 0.056262165 0.966165185
1403636742213555456 2.683764219 0.553713083 1.101755738 -0.029659156 0.248641014 0.058510933 0.966371775
1403636742263555584 2.700038910 0.573432982 1.102854967 -0.028575474 0.244833842 0.062740050 0.967110932
1403636742313555456 2.701652765 0.575555623 1.109193563 -0.026726179 0.243005976 0.063121170 0.967599869
1403636742363555584 2.696035385 0.580684066 1.118133426 -0.022152433 0.242432192 0.063084647 0.967861652
1403636742413555456 2.702253342 0.568355322 1.129730225 -0.019438777 0.241365626 0.061777633 0.968270779
1403636742463555584 2.711145401 0.580727816 1.142739296 -0.015534665 0.240237385 0.062455859 0.968578279
1403636742513555456 2.715685844 0.582248271 1.144795299 -0.013511241 0.239341959 0.061523885 0.968889952
1403636742563555584 2.717319965 0.580370128 1.151990175 -0.012520868 0.238346696 0.060551364 0.969209790
1403636742613555456 2.731664658 0.583266795 1.153041601 -0.010039455 0.237211153 0.060755305 0.969504476
1403636742663555584 2.736031055 0.575644970 1.165176630 -0.007938825 0.237192348 0.059927631 0.969580054
1403636742713555456 2.740286827 0.573942721 1.167272329 -0.005995435 0.236495107 0.058388051 0.969858229
1403636742763555584 2.745446682 0.580772340 1.175839901 -0.003666653 0.236016110 0.058085468 0.970004678
1403636742813555456 2.751223087 0.591006279 1.184490681 -0.001814916 0.235236794 0.057865199 0.970212340
1403636742863555584 2.752761602 0.605011702 1.200248480 0.000219982 0.234795883 0.058227248 0.970299184
1403636742913555456 2.760554790 0.612080216 1.199606895 0.000621701 0.233622178 0.058433969 0.970569849
1403636742963555584 2.766067982 0.621963978 1.202701807 0.000614116 0.233895257 0.059875041 0.970416188
1403636743013555456 2.771202087 0.636241555 1.220838070 -0.001688088 0.236135483 0.061012223 0.969801366
1403636743063555584 2.776218891 0.635442913 1.219830513 -0.008434839 0.238870084 0.063896991 0.968910277
1403636743113555456 2.783376217 0.653794587 1.229766130 -0.016658630 0.240732476 0.067630850 0.968089044
1403636743163555584 2.793355942 0.679877162 1.230840564 -0.026847750 0.242334455 0.072017178 0.967143595
1403636743213555456 2.798974276 0.707386255 1.250085354 -0.034148116 0.244710818 0.075203657 0.966071904
1403636743263555584 2.812038660 0.713919878 1.258133888 -0.043351829 0.246578589 0.077542327 0.965042412
1403636743313555456 2.820027351 0.738476694 1.271324992 -0.045720190 0.247566074 0.080096096 0.964471519
1403636743363555584 2.825649023 0.739663482 1.288846493 -0.047567800 0.248915777 0.082240403 0.963854134
1403636743413555456 2.830585480 0.739287794 1.292934060 -0.047846507 0.250020176 0.083861306 0.963414729
1403636743463555584 2.842608929 0.743077517 1.304248333 -0.044084392 0.251065940 0.083242238 0.963375926
1403636743513555456 2.859393120 0.738623142 1.332072854 -0.041247722 0.252506882 0.082768664 0.963165760
1403636743563555584 2.887814999 0.753810525 1.338265181 -0.035721965 0.252322942 0.081170991 0.963570595
1403636743613555456 2.898177385 0.756106853 1.356838465 -0.031327568 0.253612429 0.076740988 0.963747978
1403636743663555584 2.906232595 0.759573400 1.373046398 -0.028024454 0.254902512 0.073815718 0.963737845
1403636743713555456 2.917971134 0.759005249 1.398481250 -0.023983048 0.257019967 0.071241453 0.963478208
1403636743763555584 2.934804201 0.765652537 1.420089126 -0.019152977 0.259712964 0.068365082 0.963072479
1403636743813555456 2.955747604 0.775162518 1.436530232 -0.016119957 0.262340009 0.068170637 0.962429523
1403636743863555584 2.971673012 0.806178331 1.467767715 -0.010820569 0.264892608 0.072353020 0.961498737
1403636743913555456 3.000049114 0.811973274 1.486350060 -0.008477656 0.267907321 0.070397943 0.960831881
1403636743963555584 3.003704548 0.812017977 1.503808260 -0.006483378 0.271200925 0.070121542 0.959943235
1403636744013555456 3.012810230 0.821847558 1.517251372 -0.005425820 0.273179919 0.069662705 0.959421873
1403636744063555584 3.037663698 0.835513353 1.544952869 -0.004741030 0.276686907 0.069326222 0.958444476
1403636744113555456 3.049929380 0.860900462 1.569209456 -0.003157975 0.280842930 0.069917440 0.957198441
1403636744163555584 3.068358183 0.883323252 1.596185923 -0.001519251 0.284759939 0.071760960 0.955907881
1403636744213555456 3.085319519 0.888137341 1.616799116 -0.001086912 0.287658244 0.074369617 0.954840660
1403636744263555584 3.098834276 0.911550999 1.638978243 0.001317967 0.289877623 0.077132456 0.953949571
1403636744313555456 3.111115932 0.934770465 1.671904325 0.002538267 0.292422801 0.079167850 0.953003109
1403636744363555584 3.119756699 0.966213822 1.693989038 0.004361392 0.293358445 0.082818463 0.952398479
1403636744413555456 3.132962942 0.990615785 1.727935076 0.005349732 0.293580145 0.085705675 0.952069640
1403636744463555584 3.152138948 1.023156404 1.750757694 0.006908436 0.292487800 0.090771250 0.951926291
1403636744513555456 3.170281649 1.043666601 1.766711235 0.007859119 0.290000588 0.096680298 0.952098131
1403636744563555584 3.173684120 1.076814294 1.795099258 0.010816392 0.290385991 0.096198291 0.952000439
1403636744613555456 3.186145782 1.109432459 1.821208000 0.012902824 0.289605349 0.098963797 0.951928794
1403636744663555584 3.201185226 1.142244339 1.849758387 0.014856250 0.289312840 0.099080063 0.951977134
1403636744713555456 3.219968319 1.166929126 1.859880209 0.015560110 0.289230973 0.096149027 0.952291310
1403636744763555584 3.230938435 1.198643088 1.886332393 0.014833266 0.291791320 0.090029515 0.952120006
1403636744813555456 3.242341280 1.240123987 1.908426046 0.013765812 0.293273598 0.086211070 0.952033997
1403636744863555584 3.263120651 1.271037102 1.921087027 0.010936839 0.293553263 0.082953893 0.952273846
1403636744913555456 3.280166626 1.304498792 1.929454446 0.006012549 0.293820143 0.081066050 0.952398002
1403636744963555584 3.294837236 1.337105989 1.952196836 0.003401935 0.293805599 0.080578052 0.952456772
1403636745013555456 3.305661678 1.366786003 1.961094618 -0.001099182 0.292668641 0.081076376 0.952769876
1403636745063555584 3.320878029 1.390987277 1.973281145 -0.004908632 0.290971547 0.080299392 0.953343332
1403636745113555456 3.328598976 1.412653565 1.983958244 -0.009409682 0.289310277 0.082004093 0.953669906
1403636745163555584 3.347695112 1.433662057 1.994928956 -0.010660102 0.286292434 0.084349439 0.954362690
1403636745213555456 3.355647564 1.457470179 2.006998062 -0.011314014 0.285012215 0.082205854 0.954925239
1403636745263555584 3.367008924 1.467623234 2.017100811 -0.013438834 0.283052713 0.080249131 0.955646694
1403636745313555456 3.387601376 1.484715939 2.022816658 -0.012564383 0.280387163 0.078665480 0.956575572
1403636745363555584 3.395847321 1.497584820 2.043449879 -0.008817662 0.279646814 0.075604580 0.957080901
1403636745413555456 3.400495529 1.506372571 2.055290222 -0.004061721 0.279641420 0.072079748 0.957386374
1403636745463555584 3.425194502 1.510081053 2.053331137 -0.001235779 0.277981788 0.069986768 0.958032608
1403636745513555456 3.439790726 1.521367311 2.067904234 0.002431474 0.278042167 0.069292270 0.958063245
1403636745563555584 3.450008392 1.530373573 2.079790831 0.004304906 0.279337645 0.069304809 0.957678854
1403636745613555456 3.465440273 1.531498313 2.087137222 0.004907640 0.280500472 0.069906831 0.957292259
1403636745663555584 3.479931831 1.534520268 2.089254856 0.005825671 0.282230765 0.070148371 0.956760705
1403636745713555456 3.488280296 1.535836339 2.096394539 0.006511628 0.285484791 0.070126325 0.955792010
1403636745763555584 3.500276327 1.535209417 2.102369308 0.005553613 0.288883567 0.069054082 0.954854429
1403636745813555456 3.504672050 1.532715201 2.105512142 0.004339028 0.292537779 0.068953797 0.953754783
1403636745863555584 3.515727043 1.530571103 2.110248089 0.003442045 0.296292663 0.067837410 0.952678800
1403636745913555456 3.520391464 1.525886774 2.117765427 0.002965085 0.300555229 0.066555716 0.951434791
1403636745963555584 3.523701668 1.519240379 2.116518974 0.001662885 0.305242062 0.064473167 0.950088263
1403636746013555456 3.531581163 1.504223585 2.114284039 0.000101106 0.308797181 0.063607641 0.948998630
1403636746063555584 3.541086197 1.500546813 2.109483719 -0.000808768 0.311337560 0.061982900 0.948275506
1403636746113555456 3.544808149 1.490954041 2.114346981 -0.003187292 0.314765126 0.060031064 0.947263956
1403636746163555584 3.544111252 1.479152679 2.118983030 -0.002822472 0.317528188 0.059537966 0.946373641
1403636746213555456 3.542545319 1.463304162 2.121844769 -0.001078405 0.319738001 0.059276056 0.945649385
1403636746263555584 3.535371304 1.447958231 2.124744415 0.003478806 0.321690589 0.058330424 0.945039988
1403636746313555456 3.532388687 1.427425742 2.122860909 0.010961028 0.323413521 0.056544255 0.944503188
1403636746363555584 3.527818680 1.414797306 2.124572515 0.017334173 0.323735058 0.056773990 0.944283783
1403636746413555456 3.521814823 1.410078049 2.122959852 0.021516070 0.323892802 0.057215851 0.944116950
1403636746463555584 3.510998964 1.402247071 2.125844717 0.020014230 0.322695345 0.060329460 0.944366157
1403636746513555456 3.503031254 1.395846248 2.121204138 0.015660547 0.320561439 0.064034022 0.944931090
1403636746563555584 3.490659714 1.391638517 2.121196270 0.007518494 0.317525297 0.070230268 0.945615590
1403636746613555456 3.480651855 1.388595581 2.122450829 -0.003037457 0.313812971 0.075571783 0.946467698
1403636746663555584 3.464980602 1.385768771 2.122256756 -0.013025268 0.309810549 0.083325431 0.947050512
1403636746713555456 3.449847460 1.382655978 2.130415678 -0.022399895 0.305625379 0.091304116 0.947499275
1403636746763555584 3.438692570 1.384363532 2.133517265 -0.027105048 0.301202893 0.098202087 0.948102593
1403636746813555456 3.426019669 1.380950332 2.142327785 -0.028212011 0.298204809 0.103396498 0.948465705
1403636746863555584 3.412527800 1.382065535 2.144272804 -0.027374184 0.295688868 0.106901169 0.948889315
1403636746913555456 3.404140472 1.383009553 2.150949955 -0.025421506 0.293670118 0.108333245 0.949407995
1403636746963555584 3.400354862 1.378677368 2.161714077 -0.024571136 0.292553991 0.107397914 0.949881077
1403636747013555456 3.394399643 1.373637438 2.165528774 -0.022241961 0.291921794 0.106552750 0.950228095
1403636747063555584 3.392547607 1.369165182 2.167462826 -0.019396022 0.292659134 0.100263886 0.950747907
1403636747113555456 3.389264584 1.362535000 2.177693844 -0.016609749 0.295065194 0.093058653 0.950789571
1403636747163555584 3.386421680 1.352311015 2.179923534 -0.012926463 0.296207160 0.088550337 0.950922191
1403636747213555456 3.383891582 1.334350228 2.187066078 -0.011817572 0.298601300 0.082159378 0.950761497
1403636747263555584 3.377930164 1.321721196 2.194864273 -0.009749242 0.301044434 0.077620097 0.950395823
1403636747313555456 3.371646643 1.307142973 2.201879978 -0.008969720 0.302867174 0.075163230 0.950021863
1403636747363555584 3.377173901 1.288249969 2.203745604 -0.008646701 0.302936673 0.074434429 0.950060070
1403636747413555456 3.370630264 1.273097038 2.217771530 -0.007961736 0.304667592 0.073249646 0.949604511
1403636747463555584 3.368128777 1.256291151 2.220014334 -0.007922729 0.305715531 0.072886497 0.949295938
1403636747513555456 3.363195658 1.248489261 2.230923653 -0.008135020 0.306869328 0.074723132 0.948778927
1403636747563555584 3.359346390 1.227069139 2.237458467 -0.010545840 0.307632476 0.075881056 0.948416114
1403636747613555456 3.352433681 1.221383333 2.249879122 -0.010299595 0.308401614 0.077402279 0.948046029
1403636747663555584 3.347926140 1.206115961 2.251799345 -0.011356230 0.309205443 0.077842228 0.947736025
1403636747713555456 3.346467733 1.191935301 2.253504992 -0.011070232 0.309774697 0.079678744 0.947400868
1403636747763555584 3.337086201 1.174100995 2.268224716 -0.012174214 0.311505467 0.079196088 0.946860135
1403636747813555456 3.331991196 1.155451298 2.278895378 -0.012214020 0.312403917 0.080500655 0.946453512
1403636747863555584 3.323529005 1.135580182 2.287982225 -0.010810634 0.313337654 0.081922017 0.946039855
1403636747913555456 3.318606377 1.109713435 2.292123795 -0.008447726 0.312143952 0.088768832 0.945840836
1403636747963555584 3.311375380 1.081701994 2.301661491 -0.003515859 0.310805738 0.096551709 0.945550203
1403636748013555456 3.306137085 1.061666250 2.312302589 0.000093904 0.309548616 0.104131810 0.945164621
1403636748063555584 3.301960945 1.035825491 2.317136765 0.001551643 0.308630139 0.109654889 0.944839060
1403636748113555456 3.296838284 1.019844413 2.324259043 0.002149623 0.308715701 0.112170003 0.944514632
1403636748163555584 3.292438745 1.001051903 2.330809355 0.002357173 0.308746457 0.116146654 0.944023311
1403636748213555456 3.290232658 0.987930596 2.342324972 0.001511844 0.310092300 0.114734434 0.943756580
1403636748263555584 3.287384510 0.976801395 2.349597931 -0.000958101 0.312135756 0.109486692 0.943707049
1403636748313555456 3.285191774 0.961963415 2.359053135 -0.003976812 0.315057904 0.102543756 0.943508089
1403636748363555584 3.291460276 0.948330879 2.363569498 -0.007426480 0.317265421 0.095250152 0.943512022
1403636748413555456 3.288127899 0.937952936 2.376660585 -0.009338514 0.319598615 0.087551802 0.943453312
1403636748463555584 3.286941528 0.930441499 2.386360645 -0.008710309 0.320566744 0.084489860 0.943410099
1403636748513555456 3.288439035 0.917414904 2.389236927 -0.008658065 0.321107894 0.081023291 0.943530619
1403636748563555584 3.288085938 0.901326895 2.401389599 -0.008349233 0.321483940 0.080851465 0.943420053
1403636748613555456 3.290947437 0.884404421 2.410357237 -0.006048591 0.320356607 0.084396668 0.943510592
1403636748663555584 3.290117741 0.868134856 2.412614822 -0.003827672 0.319162250 0.088114955 0.943587065
1403636748713555456 3.292425871 0.848304451 2.423783302 -0.001638790 0.317956090 0.092894137 0.943542242
1403636748763555584 3.286478519 0.833346367 2.431604385 0.000410248 0.317430407 0.097092576 0.943297803
1403636748813555456 3.290440798 0.814377785 2.430137396 0.001385742 0.316200167 0.101308830 0.943266690
1403636748863555584 3.293161392 0.797680140 2.433405399 0.002487305 0.315967351 0.104197457 0.943027735
1403636748913555456 3.292402029 0.784109235 2.443960190 0.003899352 0.316885263 0.106702492 0.942434669
1403636748963555584 3.290802240 0.773216486 2.452339411 0.004912320 0.318620116 0.107666843 0.941735029
1403636749013555456 3.294475555 0.761307716 2.454464436 0.005338843 0.319463611 0.109182984 0.941272318
1403636749063555584 3.299752474 0.753675580 2.463349342 0.007097775 0.319794565 0.112609684 0.940744460
1403636749113555456 3.303686142 0.745667040 2.467758894 0.009281988 0.319649071 0.116666898 0.940280378
1403636749163555584 3.312460423 0.733075321 2.469876051 0.009929569 0.320066690 0.118814625 0.939862669
1403636749213555456 3.310054779 0.726284146 2.475231647 0.010263940 0.322134793 0.117711484 0.939291120
1403636749263555584 3.318438292 0.714695394 2.474609375 0.008331209 0.325348049 0.111742437 0.938931763
1403636749313555456 3.329003096 0.706226468 2.473601818 0.007772877 0.328086615 0.106304921 0.938614964
1403636749363555584 3.337329388 0.686572552 2.468404770 0.005094462 0.329916209 0.101702251 0.938502014
1403636749413555456 3.344764233 0.675095081 2.466891527 0.003634899 0.332185447 0.097381331 0.938166559
1403636749463555584 3.352231026 0.662138939 2.464792490 0.002178795 0.333731502 0.092647791 0.938101768
1403636749513555456 3.362647772 0.646420777 2.458894730 0.000529970 0.334897220 0.088644430 0.938075542
1403636749563555584 3.370926380 0.631029963 2.450568676 -0.001462353 0.336004972 0.084108829 0.938096046
1403636749613555456 3.377133131 0.614181340 2.450709581 -0.002115130 0.337467790 0.079362608 0.937983274
1403636749663555584 3.379971027 0.599779248 2.450306892 -0.002682305 0.337657928 0.078178048 0.938012838
1403636749713555456 3.386546135 0.586856484 2.441892862 -0.001262311 0.336294085 0.078349657 0.938491344
1403636749763555584 3.385703564 0.577528775 2.445307732 0.001872975 0.336160719 0.078239866 0.938547313
1403636749813555456 3.392402887 0.568474889 2.440806389 0.006329925 0.334922254 0.077796794 0.939007282
1403636749863555584 3.394278288 0.557127059 2.445838690 0.011117999 0.334025174 0.077809751 0.939281285
1403636749913555456 3.401163578 0.556980371 2.445406914 0.015123032 0.332449824 0.077524439 0.939807653
1403636749963555584 3.397980690 0.552562475 2.443361521 0.018238207 0.331158847 0.076320559 0.940306544
1403636750013555456 3.397444248 0.543116212 2.438089609 0.019406799 0.329261422 0.076672740 0.940920591
1403636750063555584 3.397302628 0.544625163 2.436492443 0.020658974 0.327436268 0.076630004 0.941534162
1403636750113555456 3.393795252 0.539086282 2.433995247 0.018928383 0.325818092 0.077374756 0.942070842
1403636750163555584 3.393198490 0.538757026 2.431616783 0.017090557 0.324071139 0.077802375 0.942673087
1403636750213555456 3.386850357 0.534502923 2.425585032 0.015325386 0.322399110 0.078454204 0.943222642
1403636750263555584 3.382238388 0.527427614 2.417252064 0.011718100 0.320830017 0.079216182 0.943745494
1403636750313555456 3.372757435 0.519643068 2.412494421 0.009381700 0.319144964 0.079856955 0.944288850
1403636750363555584 3.365561008 0.512261033 2.403324366 0.006347308 0.318068862 0.078857191 0.944761038
1403636750413555456 3.357544184 0.502073586 2.391324282 0.005245954 0.315966934 0.080945998 0.945296347
1403636750463555584 3.353728533 0.493295103 2.384437799 0.004145762 0.314357340 0.079799347 0.945935667
1403636750513555456 3.342776537 0.475365937 2.374379396 0.004408124 0.312694728 0.079168707 0.946538389
1403636750563555584 3.333741665 0.456380665 2.360954762 0.003235125 0.311030179 0.078416444 0.947153986
1403636750613555456 3.325801849 0.439846724 2.349870205 0.002473166 0.309119046 0.078340545 0.947788000
1403636750663555584 3.316447258 0.422402918 2.335159302 0.002166110 0.308591932 0.076080956 0.948144495
1403636750713555456 3.307772398 0.400504768 2.316179037 0.001391412 0.306748450 0.075663306 0.948777378
1403636750763555584 3.301689148 0.377542675 2.299342632 0.000031096 0.305323184 0.075731196 0.949232578
1403636750813555456 3.294684410 0.354368746 2.283638477 -0.000791847 0.304474413 0.075180203 0.949548662
1403636750863555584 3.274672031 0.325804770 2.272160053 -0.001962662 0.304441750 0.074159034 0.949637711
1403636750913555456 3.266201019 0.298876971 2.255222797 -0.004203327 0.304400802 0.073180370 0.949719489
1403636750963555584 3.255793571 0.273444891 2.236087561 -0.005534831 0.304268420 0.071735002 0.949865341
1403636751013555456 3.244419813 0.244380757 2.223778963 -0.007597521 0.304668248 0.070517838 0.949814081
1403636751063555584 3.227251291 0.217770308 2.210303783 -0.008152281 0.305554032 0.070417047 0.949532330
1403636751113555456 3.220554352 0.193071529 2.194227457 -0.008544956 0.305072635 0.071229026 0.949623108
1403636751163555584 3.201062918 0.173416227 2.184230328 -0.010432363 0.305760294 0.073106252 0.949240386
1403636751213555456 3.192473888 0.151771590 2.173353195 -0.015214330 0.306130350 0.073535807 0.949023306
1403636751263555584 3.178270817 0.125214130 2.158666849 -0.019945392 0.305507302 0.076464213 0.948904991
1403636751313555456 3.165839195 0.111796796 2.150122404 -0.021207614 0.305173784 0.078935914 0.948782563
1403636751363555584 3.155658245 0.091313064 2.138289690 -0.020320084 0.304479986 0.083506726 0.948633552
1403636751413555456 3.139580250 0.070005357 2.131972313 -0.017158359 0.304425746 0.086669944 0.948429644
1403636751463555584 3.134256363 0.036651582 2.128495216 -0.012984290 0.303610861 0.092549376 0.948201656
1403636751513555456 3.124895096 0.018888652 2.118393421 -0.008387866 0.302069664 0.095332883 0.948469937
1403636751563555584 3.109763861 0.000891089 2.114322662 -0.003893999 0.299972922 0.096671090 0.949028909
1403636751613555456 3.100328445 -0.017739907 2.105340958 -0.001688099 0.296362311 0.098560311 0.949974954
1403636751663555584 3.090293407 -0.037285775 2.095432997 -0.001650670 0.293090522 0.099619351 0.950879157
1403636751713555456 3.085573673 -0.053776234 2.088069439 -0.004214448 0.289620608 0.100750946 0.951814771
1403636751763555584 3.079891920 -0.071386814 2.075894117 -0.008225963 0.286301255 0.102525033 0.952603042
1403636751813555456 3.068249226 -0.088497460 2.067320347 -0.012768968 0.283792794 0.103894889 0.953154981
1403636751863555584 3.065665007 -0.109619021 2.058874369 -0.018792575 0.282555491 0.102074094 0.953619480
1403636751913555456 3.064300776 -0.113021076 2.050013304 -0.021851540 0.281933755 0.096943267 0.954273462
1403636751963555584 3.066167355 -0.126749218 2.048678637 -0.025104376 0.282297373 0.092111662 0.954564512
1403636752013555456 3.057933807 -0.147038966 2.037862778 -0.027307535 0.282955855 0.087700725 0.954724491
1403636752063555584 3.060078144 -0.168248266 2.041130066 -0.027287053 0.283558875 0.084678181 0.954819024
1403636752113555456 3.054406166 -0.185486645 2.040060282 -0.025975991 0.284349501 0.082529090 0.954808652
1403636752163555584 3.058035374 -0.196759135 2.028780937 -0.021167595 0.283037066 0.079822697 0.955547094
1403636752213555456 3.059917450 -0.216959119 2.027030230 -0.016451774 0.281378806 0.077495061 0.956320941
1403636752263555584 3.057144880 -0.231993303 2.026845932 -0.012178216 0.277938455 0.074510075 0.957627356
1403636752313555456 3.068262577 -0.246479422 2.021148205 -0.006117300 0.272226453 0.071537353 0.959550798
1403636752363555584 3.072189569 -0.271904171 2.015264511 -0.002163186 0.265745848 0.068720825 0.961588204
1403636752413555456 3.068035126 -0.289432615 2.010584116 0.000656533 0.258950680 0.065229021 0.963685274
1403636752463555584 3.067329884 -0.312451601 2.008220673 0.000890504 0.250514001 0.062827237 0.966071784
1403636752513555456 3.076973438 -0.336792707 2.001585007 0.000406990 0.240542054 0.059033543 0.968841791
1403636752563555584 3.061016083 -0.357028544 1.994333982 -0.001118494 0.232130662 0.054699648 0.971144676
1403636752613555456 3.061121941 -0.374857247 1.995290041 -0.002434479 0.222418532 0.050684776 0.973629892
1403636752663555584 3.071085453 -0.397950679 1.982041597 -0.005524689 0.211001202 0.046560042 0.976360679
1403636752713555456 3.067547798 -0.421984941 1.970317721 -0.006333539 0.200516522 0.043456286 0.978705525
1403636752763555584 3.062095165 -0.431122363 1.969898939 -0.007263385 0.190088779 0.039828986 0.980931759
1403636752813555456 3.061038733 -0.436977774 1.963228226 -0.007938385 0.179422677 0.033984635 0.983152866
1403636752863555584 3.064483166 -0.454881072 1.962872505 -0.010214617 0.168401226 0.028718909 0.985247135
1403636752913555456 3.062975645 -0.471318662 1.960684776 -0.010468098 0.158090696 0.021310791 0.987139106
1403636752963555584 3.067884207 -0.479120016 1.965811253 -0.010857115 0.147103861 0.014426281 0.988956213
1403636753013555456 3.065598488 -0.471915632 1.962744713 -0.011028168 0.136361420 0.007805134 0.990567029
1403636753063555584 3.058698893 -0.492337763 1.964592457 -0.013386778 0.125438645 0.000466324 0.992010951
1403636753113555456 3.051625729 -0.488320649 1.972430944 -0.013374236 0.113792978 -0.005016651 0.993401766
1403636753163555584 3.046973467 -0.484129250 1.967826486 -0.013480734 0.102004573 -0.010221406 0.994640052
1403636753213555456 3.043147326 -0.483452529 1.966348886 -0.013908061 0.089663699 -0.015702987 0.995751202
1403636753263555584 3.041918039 -0.482864648 1.964634538 -0.014356421 0.077520363 -0.023479598 0.996610880
1403636753313555456 3.034859419 -0.479315072 1.966139317 -0.014520472 0.066433020 -0.031186670 0.997197688
1403636753363555584 3.025933266 -0.478760630 1.973642588 -0.013254271 0.054876082 -0.036580902 0.997734845
1403636753413555456 3.024084806 -0.463415802 1.975520492 -0.011305223 0.044335071 -0.038041558 0.998228133
1403636753463555584 3.026397228 -0.466127574 1.964286685 -0.011012753 0.034174465 -0.036463019 0.998689771
1403636753513555456 3.013105154 -0.455437243 1.971860170 -0.009714368 0.027217107 -0.034658883 0.998981297
1403636753563555584 3.002717257 -0.457413286 1.969578028 -0.009296050 0.020806706 -0.032795247 0.999202251
1403636753613555456 3.001536369 -0.453473300 1.968574286 -0.007095336 0.015889365 -0.031480111 0.999352872
1403636753663555584 2.987983704 -0.465024650 1.966158032 -0.007427911 0.013318162 -0.030861327 0.999407351
1403636753713555456 2.972116470 -0.469015688 1.969467163 -0.007536274 0.011862701 -0.029690156 0.999460340
1403636753763555584 2.959520817 -0.472520590 1.968769073 -0.006756740 0.011365712 -0.030291991 0.999453604
1403636753813555456 2.948072910 -0.483099729 1.959119678 -0.006582799 0.011497538 -0.031398788 0.999419093
1403636753863555584 2.939624310 -0.471132874 1.966572404 -0.005090713 0.011952001 -0.031286385 0.999426007
1403636753913555456 2.927852392 -0.463882208 1.966833949 -0.004978818 0.012134786 -0.029472345 0.999479532
1403636753963555584 2.912211657 -0.464812964 1.966157436 -0.004894197 0.013606745 -0.029710671 0.999453962
1403636754013555456 2.902297020 -0.454653800 1.969659090 -0.003611194 0.014864058 -0.029731596 0.999440849
1403636754063555584 2.886834860 -0.460942656 1.968355298 -0.001324605 0.016697638 -0.029497257 0.999424517
1403636754113555456 2.877391815 -0.456273228 1.966781497 0.002543315 0.017339898 -0.028636919 0.999436200
1403636754163555584 2.857590914 -0.471420020 1.963475823 0.004225430 0.019256007 -0.029587233 0.999367774
1403636754213555456 2.839285135 -0.466699064 1.960829854 0.007446110 0.021606090 -0.030381568 0.999277115
1403636754263555584 2.826865196 -0.474105537 1.953662872 0.007986322 0.023443321 -0.031491239 0.999197125
1403636754313555456 2.814762115 -0.481619239 1.947955608 0.007808419 0.024786130 -0.032467939 0.999134898
1403636754363555584 2.804382086 -0.478004396 1.931539774 0.008622489 0.025363429 -0.033119559 0.999092340
1403636754413555456 2.792196512 -0.480747521 1.917373657 0.008824257 0.024487829 -0.032776210 0.999123693
1403636754463555584 2.770858288 -0.486013681 1.908505321 0.008286321 0.022897013 -0.033578221 0.999139428
1403636754513555456 2.753538132 -0.483491868 1.895889640 0.007885245 0.020396309 -0.034868851 0.999152601
1403636754563555584 2.738198757 -0.488016009 1.882488370 0.005961569 0.016308591 -0.036919355 0.999167383
1403636754613555456 2.716329813 -0.498258710 1.867232323 0.003374663 0.011311182 -0.040295888 0.999118090
1403636754663555584 2.707889080 -0.481303781 1.848837733 0.004337054 0.003885124 -0.041745547 0.999111295
1403636754713555456 2.674816608 -0.485813826 1.837441921 0.002574274 -0.002841846 -0.043763813 0.999034524
1403636754763555584 2.657622814 -0.482554197 1.815619707 0.002822042 -0.011508366 -0.046285540 0.998857975
1403636754813555456 2.640829325 -0.466540337 1.806323409 0.003742064 -0.020039378 -0.047607157 0.998658121
1403636754863555584 2.623353481 -0.458438903 1.790173173 0.003697098 -0.028097915 -0.048708819 0.998410881
1403636754913555456 2.595301628 -0.452398956 1.785171747 0.003954188 -0.033432256 -0.051826950 0.998088479
1403636754963555584 2.581791162 -0.438439727 1.764186382 0.004039052 -0.040241510 -0.052118871 0.997821569
1403636755013555456 2.553465128 -0.437687904 1.752607703 0.002885420 -0.043875393 -0.055917241 0.997466743
1403636755063555584 2.528243542 -0.423540831 1.732600331 0.003517689 -0.047467612 -0.055302482 0.997334480
1403636755113555456 2.499922752 -0.413730770 1.716136456 0.003234598 -0.049944572 -0.056354709 0.997155547
1403636755163555584 2.478680849 -0.401713461 1.700983524 0.002982580 -0.053408384 -0.056040548 0.996994495
1403636755213555456 2.446082354 -0.407050967 1.681793451 0.001638421 -0.054812517 -0.056762584 0.996880591
1403636755263555584 2.429996967 -0.388552397 1.658429861 0.000253607 -0.056737907 -0.055725671 0.996832669
1403636755313555456 2.404100418 -0.390672237 1.633718848 -0.005654738 -0.057530828 -0.056419730 0.996732175
1403636755363555584 2.370631933 -0.390655458 1.619851708 -0.011956449 -0.057362497 -0.056588937 0.996676624
1403636755413555456 2.348450899 -0.394226521 1.593855619 -0.017638618 -0.057755850 -0.057828426 0.996498406
1403636755463555584 2.327478170 -0.390107900 1.571143270 -0.020836106 -0.058197916 -0.057136714 0.996450841
1403636755513555456 2.303137302 -0.389002979 1.548866630 -0.021378409 -0.057569977 -0.057277966 0.996467710
1403636755563555584 2.269413710 -0.388470888 1.529870272 -0.021331882 -0.055789474 -0.058468625 0.996500850
1403636755613555456 2.244117498 -0.390540838 1.513950109 -0.019707290 -0.055187471 -0.059868019 0.996484756
1403636755663555584 2.223312140 -0.384164989 1.488510966 -0.018040454 -0.055395048 -0.057851758 0.996623874
1403636755713555456 2.193252087 -0.384726048 1.473415375 -0.017661467 -0.054924767 -0.057611108 0.996670663
1403636755763555584 2.162889957 -0.378483653 1.457398057 -0.015733739 -0.054479230 -0.055557627 0.996843934
1403636755813555456 2.131144762 -0.371428013 1.440651894 -0.012694419 -0.054158531 -0.054173641 0.996980965
1403636755863555584 2.103515863 -0.370982885 1.424631834 -0.011679385 -0.054526575 -0.053209167 0.997025192
1403636755913555456 2.074770689 -0.366464585 1.411210895 -0.009153769 -0.054173030 -0.053563960 0.997051835
1403636755963555584 2.044634581 -0.358876526 1.394285202 -0.008374897 -0.054517087 -0.052049637 0.997120142
1403636756013555456 2.020419598 -0.350185424 1.373942375 -0.006845281 -0.055047277 -0.050776958 0.997168303
1403636756063555584 1.988739848 -0.349531978 1.362491965 -0.006107595 -0.055405729 -0.050496846 0.997167468
1403636756113555456 1.954914927 -0.348094374 1.344761133 -0.005534904 -0.054467600 -0.052158114 0.997137010
1403636756163555584 1.928331256 -0.340357423 1.327327013 -0.003648512 -0.054974403 -0.052185912 0.997116387
1403636756213555456 1.892623782 -0.343580902 1.310931325 -0.002554590 -0.054629177 -0.052197039 0.997138202
1403636756263555584 1.864560246 -0.343619585 1.288482189 -0.002250898 -0.055212703 -0.051580917 0.997138858
1403636756313555456 1.834930778 -0.342018187 1.269622803 -0.002066408 -0.055610511 -0.051514946 0.997120559
1403636756363555584 1.798856378 -0.344299257 1.255560994 -0.001932255 -0.055584647 -0.052511144 0.997070312
1403636756413555456 1.771746993 -0.338252634 1.236556292 -0.001056298 -0.055832278 -0.053214032 0.997020483
1403636756463555584 1.747549057 -0.336395562 1.213436246 -0.000997885 -0.056892805 -0.052614305 0.996992469
1403636756513555456 1.719040871 -0.323589712 1.196007490 -0.000249194 -0.057834968 -0.051702768 0.996986389
1403636756563555584 1.679594517 -0.318148702 1.181960344 -0.000220670 -0.057339467 -0.052599683 0.996968091
1403636756613555456 1.651180148 -0.307744473 1.163759708 0.000411574 -0.058120694 -0.052191161 0.996944308
1403636756663555584 1.618735075 -0.302004755 1.144422650 0.000413741 -0.058671821 -0.052150562 0.996914089
1403636756713555456 1.589080572 -0.292009711 1.124972105 0.001797388 -0.059440315 -0.052116379 0.996868849
1403636756763555584 1.558751702 -0.286562830 1.100679159 0.002495885 -0.059968844 -0.052170232 0.996832848
1403636756813555456 1.525202632 -0.282718718 1.085353136 0.003016292 -0.060465667 -0.051698051 0.996825993
1403636756863555584 1.496805191 -0.276680022 1.061743140 0.003019149 -0.061286733 -0.051076986 0.996807873
1403636756913555456 1.463372350 -0.277786732 1.038441896 0.002462676 -0.061319970 -0.051817559 0.996769130
1403636756963555584 1.433880210 -0.278036833 1.009757400 0.002010203 -0.062147144 -0.051317967 0.996744752
1403636757013555456 1.408403158 -0.278854191 0.985022783 0.001953000 -0.062834710 -0.051849745 0.996674240
1403636757063555584 1.374027967 -0.274899960 0.961750746 0.001553358 -0.063766703 -0.049720600 0.996724248
1403636757113555456 1.348590612 -0.273091584 0.932484388 0.001986852 -0.064242914 -0.049911890 0.996683359
1403636757163555584 1.315017462 -0.272102654 0.905547261 0.000606414 -0.064092562 -0.050493579 0.996665537
1403636757213555456 1.283736587 -0.261929750 0.882864833 0.001246923 -0.063984789 -0.050026082 0.996695399
1403636757263555584 1.255977750 -0.254091352 0.854557991 0.001265266 -0.064219460 -0.050607890 0.996650934
1403636757313555456 1.225444198 -0.244471759 0.829408467 0.000343300 -0.063428566 -0.053424280 0.996555328
1403636757363555584 1.198591709 -0.235635445 0.801083982 -0.000988867 -0.063759275 -0.053284131 0.996541321
1403636757413555456 1.168836117 -0.224000424 0.773245215 -0.002852261 -0.063803963 -0.055331361 0.996423244
1403636757463555584 1.144324422 -0.207873821 0.745722175 -0.004501772 -0.063401610 -0.057288896 0.996332228
1403636757513555456 1.113024354 -0.196516037 0.717419088 -0.006809618 -0.064365901 -0.059887514 0.996104479
1403636757563555584 1.080981255 -0.180716425 0.694767892 -0.010363671 -0.066531874 -0.061230462 0.995849848
1403636757613555456 1.050209880 -0.171108529 0.667833924 -0.016334750 -0.069921978 -0.063079789 0.995422006
1403636757663555584 1.021370888 -0.163913563 0.637091637 -0.022528753 -0.073728181 -0.064859837 0.994911969
1403636757713555456 0.990665078 -0.159985468 0.610217571 -0.028763982 -0.077178709 -0.066520907 0.994379699
1403636757763555584 0.959436417 -0.155928925 0.585330486 -0.033898924 -0.080739208 -0.066866048 0.993911982
1403636757813555456 0.925031900 -0.157620803 0.555326819 -0.038032476 -0.084127158 -0.067825630 0.993416250
1403636757863555584 0.887619376 -0.159573838 0.533133447 -0.040741675 -0.087051973 -0.067186624 0.993100226
1403636757913555456 0.855671108 -0.163074344 0.508771479 -0.040465631 -0.089923725 -0.066606000 0.992894709
1403636757963555584 0.821626961 -0.173214391 0.478547633 -0.038086921 -0.093065605 -0.065689541 0.992760301
1403636758013555456 0.784989119 -0.183861524 0.455736458 -0.030645885 -0.094967477 -0.065378025 0.992858350
1403636758063555584 0.751886129 -0.189765364 0.438595712 -0.023169791 -0.097281180 -0.064667635 0.992883503
1403636758113555456 0.715610027 -0.196199089 0.417161882 -0.016666502 -0.099174947 -0.062073801 0.992992103
1403636758163555584 0.682738364 -0.202213496 0.397696495 -0.011478915 -0.100547276 -0.061832517 0.992942691
1403636758213555456 0.647604823 -0.204757318 0.381629229 -0.006721189 -0.101492889 -0.060774025 0.992955446
1403636758263555584 0.613408685 -0.205335021 0.363911450 -0.004377299 -0.102580592 -0.059692010 0.992922425
1403636758313555456 0.581541300 -0.207732186 0.343482256 -0.003053549 -0.103616565 -0.057694614 0.992937863
1403636758363555584 0.547503233 -0.203246042 0.330563903 -0.004505348 -0.104138903 -0.057049200 0.992914975
1403636758413555456 0.513696909 -0.198551714 0.311928302 -0.011226593 -0.104562320 -0.054964308 0.992934823
1403636758463555584 0.482723147 -0.194186091 0.292818606 -0.021032551 -0.105627157 -0.051946297 0.992825329
1403636758513555456 0.451127142 -0.182815492 0.280840576 -0.032256730 -0.107196689 -0.046648040 0.992618918
1403636758563555584 0.423144162 -0.177444726 0.263443112 -0.044062085 -0.109356083 -0.040655814 0.992192984
1403636758613555456 0.392399788 -0.171949685 0.248597264 -0.053664859 -0.110655211 -0.035972923 0.991756737
1403636758663555584 0.364482045 -0.163202509 0.241226703 -0.055239942 -0.110724673 -0.034684036 0.991708398
1403636758713555456 0.336467296 -0.157211229 0.234275252 -0.048833232 -0.109948330 -0.034948278 0.992121577
1403636758763555584 0.311455011 -0.151546732 0.228593558 -0.039477665 -0.108222015 -0.037599601 0.992630720
1403636758813555456 0.285984159 -0.145688444 0.223261416 -0.030850323 -0.107633658 -0.038170010 0.992978513
1403636758863555584 0.263846904 -0.140947059 0.222120941 -0.022140274 -0.107152998 -0.040616624 0.993165851
1403636758913555456 0.240460783 -0.133756295 0.221012414 -0.016246913 -0.104907677 -0.045819234 0.993292987
1403636758963555584 0.220232144 -0.127967313 0.218359441 -0.011674161 -0.104362309 -0.048506275 0.993287206
1403636759013555456 0.200398326 -0.120042026 0.217087686 -0.009182679 -0.103986509 -0.049989175 0.993279219
1403636759063555584 0.178385556 -0.111720331 0.215795010 -0.006947650 -0.104778148 -0.048067339 0.993309021
1403636759113555456 0.158425659 -0.104463331 0.215335861 -0.006621758 -0.107349776 -0.040529661 0.993372858
1403636759163555584 0.140315652 -0.095527142 0.214216083 -0.006900454 -0.111479402 -0.029827710 0.993295074
1403636759213555456 0.123842478 -0.088035010 0.212403536 -0.008098354 -0.115313046 -0.019397780 0.993106782
1403636759263555584 0.106066540 -0.078278825 0.212185070 -0.008859099 -0.117978714 -0.010905627 0.992916703
1403636759313555456 0.094256595 -0.066544965 0.211333156 -0.009018773 -0.118951082 -0.008284040 0.992824674
1403636759363555584 0.085939944 -0.053491633 0.212974831 -0.007403883 -0.117391102 -0.014786967 0.992948115
1403636759413555456 0.078599706 -0.038530186 0.212243378 -0.006567981 -0.114752144 -0.023353975 0.993097901
1403636759463555584 0.075315043 -0.022405831 0.217154413 -0.004377273 -0.112806477 -0.031199813 0.993117392
1403636759513555456 0.070742242 -0.007247467 0.218027189 -0.003713194 -0.110144041 -0.039248936 0.993133426
1403636759563555584 0.069594927 0.008996012 0.219443440 -0.002582645 -0.109377921 -0.044376642 0.993005812
1403636759613555456 0.067280352 0.024522530 0.218511939 -0.001647886 -0.107781395 -0.050381985 0.992895842
1403636759663555584 0.065574676 0.035461899 0.216369808 -0.001900386 -0.106830560 -0.054060511 0.992804706
1403636759713555456 0.064657316 0.045843311 0.214846313 -0.002188602 -0.106778845 -0.056098375 0.992696583
1403636759763555584 0.062701792 0.053238951 0.209811017 -0.001562536 -0.107262321 -0.056250468 0.992636979
1403636759813555456 0.061666775 0.058140885 0.204511538 -0.000300403 -0.106858298 -0.057706293 0.992598176
1403636759863555584 0.061159641 0.061773796 0.198665693 -0.001503306 -0.106981993 -0.057099346 0.992618859
1403636759913555456 0.060577497 0.067304060 0.191359967 -0.006588738 -0.106655866 -0.058125719 0.992573678
1403636759963555584 0.060292955 0.072830074 0.184035882 -0.012145617 -0.106604405 -0.058325827 0.992515028
1403636760013555456 0.059497345 0.079453990 0.178931147 -0.016823957 -0.106074095 -0.058072507 0.992518425
1403636760063555584 0.059301317 0.086541995 0.172679663 -0.021187827 -0.106482372 -0.056681149 0.992471576
1403636760113555456 0.058662225 0.094050124 0.167714760 -0.025754396 -0.105605379 -0.057851508 0.992389739
1403636760163555584 0.058703359 0.101178922 0.162899137 -0.029186061 -0.105635487 -0.058075733 0.992278457
1403636760213555456 0.057872448 0.107791364 0.160020277 -0.025254928 -0.105730362 -0.057546854 0.992406964
1403636760263555584 0.057517186 0.113715194 0.156856060 -0.017927241 -0.105856173 -0.056133691 0.992633939
1403636760313555456 0.056674175 0.120426252 0.155721605 -0.010932609 -0.106822737 -0.053846017 0.992758811
1403636760363555584 0.057079554 0.127966404 0.153240815 -0.006837659 -0.106266282 -0.054811671 0.992802322
1403636760413555456 0.057901993 0.136191398 0.151210144 -0.002671082 -0.106145300 -0.056413785 0.992745459
1403636760463555584 0.058488477 0.145886764 0.148758650 -0.001227245 -0.105751500 -0.057863317 0.992706895
1403636760513555456 0.059179105 0.155497417 0.145752192 -0.002999477 -0.105074354 -0.059540417 0.992675841
1403636760563555584 0.058968864 0.166171297 0.142157644 -0.007996617 -0.104486309 -0.061867826 0.992567897
1403636760613555456 0.060105730 0.177218884 0.138368532 -0.013126085 -0.104281217 -0.062701873 0.992482543
1403636760663555584 0.061333999 0.187304884 0.134760633 -0.017047256 -0.104149528 -0.065088972 0.992283106
1403636760713555456 0.061376661 0.196891561 0.131241843 -0.020405557 -0.103494294 -0.067196377 0.992147803
1403636760763555584 0.060817793 0.204838917 0.127158120 -0.020150332 -0.103162207 -0.069372207 0.992037773
1403636760813555456 0.059987761 0.212487400 0.123478308 -0.017619159 -0.103335582 -0.070204876 0.992009401
1403636760863555584 0.057770111 0.220389783 0.120794535 -0.013594219 -0.103037633 -0.071501747 0.992011070
1403636760913555456 0.055923942 0.228298426 0.117509454 -0.010414743 -0.103128396 -0.072866410 0.991940796
1403636760963555584 0.052518852 0.236250058 0.113993004 -0.010875720 -0.103325851 -0.072973557 0.991907418
1403636761013555456 0.048762061 0.244982228 0.110043541 -0.014632912 -0.103857577 -0.071656294 0.991899610
1403636761063555584 0.044521138 0.253809065 0.105756193 -0.019502077 -0.104488894 -0.069724418 0.991887212
1403636761113555456 0.040093549 0.262336135 0.101816610 -0.026374187 -0.105422430 -0.068234578 0.991733134
1403636761163555584 0.034852222 0.271328568 0.098253764 -0.033966675 -0.105737880 -0.067545958 0.991515636
1403636761213555456 0.028920291 0.279588193 0.095003031 -0.041022819 -0.105322734 -0.069332428 0.991169631
1403636761263555584 0.022169214 0.286830515 0.093842372 -0.045462124 -0.105286226 -0.068373106 0.991046488
1403636761313555456 0.016009143 0.292092800 0.093510486 -0.046988636 -0.105565064 -0.069088668 0.990895987
1403636761363555584 0.008100027 0.295992225 0.094761945 -0.043959845 -0.105790563 -0.068304174 0.991065323
1403636761413555456 -0.000806700 0.297845423 0.096328005 -0.037096661 -0.105660006 -0.068548754 0.991342962
1403636761463555584 -0.008209616 0.297855586 0.099103823 -0.029377503 -0.106478356 -0.066653289 0.991643429
1403636761513555456 -0.017218620 0.297914863 0.101795077 -0.021592766 -0.106586985 -0.065808266 0.991888225
1403636761563555584 -0.026102848 0.297070354 0.105600722 -0.015494389 -0.106518246 -0.065954007 0.991999924
1403636761613555456 -0.034842901 0.295396954 0.107681550 -0.010919338 -0.106532387 -0.064232692 0.992172241
1403636761663555584 -0.044015318 0.293719202 0.108799584 -0.008900115 -0.107772209 -0.059815895 0.992334604
1403636761713555456 -0.053060524 0.290850192 0.110484377 -0.007948361 -0.109355576 -0.053269848 0.992542446
1403636761763555584 -0.062225521 0.288275659 0.111053266 -0.008526833 -0.110948011 -0.047357511 0.992660642
1403636761813555456 -0.069096766 0.285304666 0.113269113 -0.008532107 -0.112595484 -0.041833069 0.992723286
1403636761863555584 -0.076298878 0.281937808 0.113362513 -0.008974921 -0.113552988 -0.038513348 0.992744625
1403636761913555456 -0.081648163 0.279474586 0.113103747 -0.009689119 -0.112691231 -0.039613463 0.992792845
1403636761963555584 -0.084550388 0.275929600 0.113013528 -0.010137015 -0.111550055 -0.043146033 0.992770016
1403636762013555456 -0.088260986 0.272980988 0.115053117 -0.008360363 -0.107878685 -0.052264597 0.992754102
1403636762063555584 -0.089330070 0.269678980 0.115023717 -0.006638913 -0.104510956 -0.060712162 0.992646694
1403636762113555456 -0.092047565 0.266714513 0.114957549 -0.005017773 -0.099808529 -0.073068894 0.992307425
1403636762163555584 -0.094234824 0.263176680 0.113243908 -0.005528177 -0.096653864 -0.081470050 0.991962790
1403636762213555456 -0.098796636 0.260089338 0.111286037 -0.010141428 -0.094963223 -0.085280843 0.991769314
1403636762263555584 -0.104326978 0.257497102 0.109270200 -0.018052230 -0.094610535 -0.084840678 0.991728306
1403636762313555456 -0.111045159 0.256174803 0.106986806 -0.026475886 -0.094988950 -0.082303777 0.991716802
1403636762363555584 -0.118856989 0.256996512 0.106773764 -0.033979002 -0.095553465 -0.079629086 0.991652250
1403636762413555456 -0.127618819 0.259474128 0.108601578 -0.037854902 -0.096912771 -0.074750684 0.991759658
1403636762463555584 -0.137799665 0.262738436 0.110316932 -0.040111866 -0.099569209 -0.066650949 0.991985202
1403636762513555456 -0.149069160 0.266566724 0.113934129 -0.037209138 -0.104479626 -0.052417278 0.992447436
1403636762563555584 -0.159789875 0.271495134 0.118421234 -0.032785099 -0.108684734 -0.038692895 0.992781758
1403636762613555456 -0.170129359 0.278233528 0.125085279 -0.028170653 -0.113176398 -0.025326617 0.992852509
1403636762663555584 -0.178690970 0.288170218 0.134346217 -0.022164116 -0.115646973 -0.017516082 0.992888570
1403636762713555456 -0.184876263 0.300983906 0.146014124 -0.016935745 -0.114938207 -0.020180883 0.993023217
1403636762763555584 -0.188011885 0.314237893 0.154708639 -0.013877198 -0.113374084 -0.027537720 0.993073702
1403636762813555456 -0.189979136 0.330586970 0.166095704 -0.011529488 -0.110481910 -0.037358128 0.993108869
1403636762863555584 -0.186815634 0.331246287 0.168585896 0.019681225 -0.114702299 -0.026494566 0.992851496
1403636762913555456 -0.186976939 0.326311290 0.166072056 0.031375829 -0.111129403 -0.031034866 0.992825568
================================================
FILE: Examples/Stereo/euroc_old/CameraTrajectory_MH02.txt
================================================
1403636858651666432 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 1.000000000
1403636858701666560 0.000964637 -0.000223877 -0.000635099 -0.000965568 0.002432592 -0.000333681 0.999996543
1403636858751666432 0.003694786 -0.001992992 -0.001782172 -0.002621777 0.004408798 -0.000705580 0.999986589
1403636858801666560 0.006310861 -0.005003376 -0.003901700 -0.003862357 0.005900711 -0.000330539 0.999975085
1403636858851666432 0.010442916 -0.009727868 -0.003556680 -0.005234005 0.007411945 0.000044546 0.999958813
1403636858901666560 0.014460033 -0.016008295 -0.006966823 -0.006200943 0.010340760 0.000277020 0.999927282
1403636858951666432 0.019284301 -0.022948846 -0.009218154 -0.006862227 0.012930341 0.000236052 0.999892831
1403636859001666560 0.025123959 -0.031654976 -0.009191989 -0.007603525 0.015491726 -0.000046943 0.999851108
1403636859051666432 0.029304031 -0.040053561 -0.012616301 -0.009113731 0.017993221 -0.000270584 0.999796569
1403636859101666560 0.033493340 -0.047273371 -0.013389061 -0.011162404 0.019864434 0.000051096 0.999740362
1403636859151666432 0.039159801 -0.054782037 -0.016657833 -0.014190479 0.021582091 -0.000952517 0.999665916
1403636859201666560 0.044441450 -0.061929543 -0.018736707 -0.017059796 0.022237161 0.000158424 0.999607146
1403636859251666432 0.048316773 -0.069729358 -0.021999627 -0.019386549 0.024962049 0.000715355 0.999500155
1403636859301666560 0.052293994 -0.080058388 -0.025933133 -0.019181214 0.028153636 0.000515257 0.999419451
1403636859351666432 0.055702079 -0.091871917 -0.029555202 -0.017377349 0.031536777 -0.001107449 0.999350905
1403636859401666560 0.057426646 -0.106218867 -0.033507641 -0.015951399 0.035102293 -0.003283514 0.999251008
1403636859451666432 0.059405580 -0.123268537 -0.038904898 -0.016688673 0.037138343 -0.003234215 0.999165535
1403636859501666560 0.061070338 -0.142115608 -0.042654812 -0.019804711 0.039658736 -0.003889345 0.999009430
1403636859551666432 0.063286401 -0.162402391 -0.046195976 -0.023209678 0.042272668 -0.004762751 0.998825192
1403636859601666560 0.065064020 -0.184211344 -0.050229672 -0.023884000 0.046653550 -0.006619373 0.998603582
1403636859651666432 0.065783449 -0.207915828 -0.054202795 -0.022270860 0.051985178 -0.009640606 0.998353004
1403636859701666560 0.066674873 -0.231003478 -0.058484942 -0.017529808 0.055111606 -0.010476558 0.998271346
1403636859751666432 0.066953868 -0.253573149 -0.060619630 -0.010912356 0.059005499 -0.012821187 0.998115659
1403636859801666560 0.067395352 -0.275741577 -0.064697243 -0.005908947 0.062530994 -0.015489493 0.997905314
1403636859851666432 0.067048773 -0.296767026 -0.067703277 -0.002093387 0.066314720 -0.019847786 0.997599185
1403636859901666560 0.066529095 -0.316523671 -0.072283067 0.000281575 0.068288192 -0.021611745 0.997431517
1403636859951666432 0.066962056 -0.333750844 -0.077599019 0.001660344 0.069531441 -0.022202732 0.997331262
1403636860001666560 0.065902509 -0.348007977 -0.083076850 0.002078102 0.071436293 -0.022167044 0.997196674
1403636860051666432 0.067600034 -0.354488194 -0.084391281 0.001102013 0.073402897 -0.022498101 0.997047961
1403636860101666560 0.071192063 -0.356374234 -0.084217750 -0.001040355 0.074844435 -0.019529825 0.997003376
1403636860151666432 0.074611530 -0.349984884 -0.082826294 -0.004087240 0.074969880 -0.017451638 0.997024655
1403636860201666560 0.078095637 -0.334925473 -0.078266643 -0.008318793 0.074804649 -0.015958926 0.997035801
1403636860251666432 0.079690203 -0.314674050 -0.075019747 -0.013926021 0.073111646 -0.012324290 0.997150362
1403636860301666560 0.081713326 -0.287784159 -0.067966111 -0.021319613 0.071990401 -0.009441150 0.997132719
1403636860351666432 0.084455490 -0.261668354 -0.063958623 -0.031555030 0.072007217 -0.006275551 0.996885061
1403636860401666560 0.085201964 -0.231944233 -0.057580829 -0.042811293 0.072337434 -0.002837716 0.996456921
1403636860451666432 0.086282939 -0.203350425 -0.052084140 -0.054386601 0.072742097 -0.000325051 0.995866716
1403636860501666560 0.088059172 -0.176342100 -0.046833411 -0.065742880 0.071807832 0.004437767 0.995239556
1403636860551666432 0.088625558 -0.152054042 -0.042673152 -0.075501196 0.070145488 0.007216245 0.994649231
1403636860601666560 0.089743100 -0.131371722 -0.039633926 -0.083816573 0.068997279 0.009650613 0.994042754
1403636860651666432 0.090083882 -0.114733517 -0.039132144 -0.088932142 0.066592842 0.011251318 0.993745327
1403636860701666560 0.090334438 -0.102195196 -0.038742818 -0.091506682 0.064014055 0.010018704 0.993694246
1403636860751666432 0.090924032 -0.094712786 -0.039201643 -0.092529275 0.063756168 0.006750937 0.993643761
1403636860801666560 0.090971060 -0.092825837 -0.040875822 -0.091905572 0.063186496 0.003012807 0.993756354
1403636860851666432 0.091562025 -0.098138198 -0.043655794 -0.091918230 0.062403306 -0.001678404 0.993807852
1403636860901666560 0.091747083 -0.110241175 -0.047616459 -0.092038088 0.060939472 -0.004040289 0.993880808
1403636860951666432 0.091177627 -0.128509119 -0.053466491 -0.091205247 0.059126612 -0.006286771 0.994055450
1403636861001666560 0.090629108 -0.152074829 -0.059225488 -0.087855928 0.058773484 -0.008178759 0.994364142
1403636861051666432 0.089412063 -0.178892091 -0.065011747 -0.082153276 0.058571938 -0.009429714 0.994852364
1403636861101666560 0.089501113 -0.208812773 -0.071437091 -0.073838860 0.058614034 -0.008853937 0.995506823
1403636861151666432 0.089386418 -0.240082607 -0.078035027 -0.063776262 0.059433151 -0.010174228 0.996140957
1403636861201666560 0.089183584 -0.272371650 -0.085572071 -0.051870991 0.059510373 -0.011959829 0.996807337
1403636861251666432 0.088979810 -0.302956790 -0.092831299 -0.039641596 0.059565388 -0.013209139 0.997349501
1403636861301666560 0.089470774 -0.333048463 -0.098574772 -0.027414430 0.059208766 -0.013075032 0.997783422
1403636861351666432 0.090573423 -0.357578427 -0.104913101 -0.016103229 0.059763100 -0.013382172 0.997992933
1403636861401666560 0.090979151 -0.382678717 -0.109919734 -0.007283259 0.060652971 -0.011387307 0.998067319
1403636861451666432 0.092035688 -0.398574054 -0.113230936 0.000105300 0.061817344 -0.011943401 0.998016000
1403636861501666560 0.091663182 -0.408135176 -0.115286484 0.004702200 0.063142508 -0.011106704 0.997931600
1403636861551666432 0.094135873 -0.408915669 -0.114314541 0.005868447 0.064827323 -0.011225546 0.997816026
1403636861601666560 0.095957853 -0.401627749 -0.112195201 0.003364459 0.064991243 -0.010807586 0.997821569
1403636861651666432 0.097786874 -0.385238200 -0.106728382 -0.001460042 0.064190879 -0.009833372 0.997888088
1403636861701666560 0.098952919 -0.364464402 -0.100605965 -0.007549612 0.063003577 -0.009663800 0.997937918
1403636861751666432 0.100182392 -0.337960392 -0.093451373 -0.013324263 0.062144585 -0.009283073 0.997934997
1403636861801666560 0.100130454 -0.312447727 -0.087126337 -0.019611292 0.061870199 -0.010177584 0.997839570
1403636861851666432 0.100454696 -0.284345597 -0.080295421 -0.025337992 0.060080178 -0.009819224 0.997823536
1403636861901666560 0.099932738 -0.255810946 -0.072644532 -0.033498816 0.058201142 -0.009439319 0.997698009
1403636861951666432 0.098998651 -0.227632836 -0.066943169 -0.043464340 0.056091052 -0.006221274 0.997459710
1403636862001666560 0.096513003 -0.198645905 -0.060818285 -0.053727306 0.054797627 -0.004113678 0.997042477
1403636862051666432 0.095186606 -0.171136022 -0.054686379 -0.062805422 0.053396482 -0.001636760 0.996594965
1403636862101666560 0.092898622 -0.147635326 -0.048795503 -0.070364714 0.053125296 0.001247854 0.996104896
1403636862151666432 0.092143476 -0.124903157 -0.043863662 -0.075248986 0.050948240 0.004389057 0.995852649
1403636862201666560 0.090900078 -0.108755685 -0.041039795 -0.079121865 0.049464744 0.004007364 0.995628893
1403636862251666432 0.090633452 -0.098751307 -0.040085085 -0.083452195 0.050341688 -0.000340992 0.995239377
1403636862301666560 0.090822674 -0.095283188 -0.040334761 -0.087336324 0.050314069 -0.003665608 0.994900703
1403636862351666432 0.091171622 -0.100581497 -0.042520400 -0.091574281 0.049970515 -0.005440351 0.994528770
1403636862401666560 0.090861380 -0.114337891 -0.046718098 -0.093864076 0.049134027 -0.005557454 0.994356334
1403636862451666432 0.090086885 -0.134072900 -0.052661255 -0.092414558 0.048750289 -0.006559299 0.994504869
1403636862501666560 0.090520665 -0.158912629 -0.058752872 -0.088916585 0.049388368 -0.006836606 0.994790316
1403636862551666432 0.090683348 -0.190015048 -0.065323099 -0.084406681 0.053721812 -0.009832324 0.994933605
1403636862601666560 0.092062160 -0.221488267 -0.070252776 -0.078321487 0.059799306 -0.013919113 0.995035708
1403636862651666432 0.092914604 -0.253080726 -0.076588482 -0.070427313 0.064522572 -0.016526423 0.995290756
1403636862701666560 0.092301242 -0.286491036 -0.084003106 -0.063215002 0.067820787 -0.018810757 0.995515108
1403636862751666432 0.091091529 -0.320319444 -0.090442061 -0.056897260 0.069021203 -0.014462201 0.995886326
1403636862801666560 0.090527117 -0.356176317 -0.098717600 -0.053832151 0.071249411 -0.013101700 0.995918632
1403636862851666432 0.088518485 -0.389054060 -0.106112853 -0.050522253 0.073391810 -0.008381147 0.995987356
1403636862901666560 0.088867538 -0.418708444 -0.113108143 -0.046585582 0.073659748 -0.004961442 0.996182382
1403636862951666432 0.087503865 -0.444834501 -0.120911315 -0.041982159 0.073436789 -0.000139622 0.996415794
1403636863001666560 0.087607093 -0.459241480 -0.125641704 -0.035773084 0.072409302 0.000490875 0.996733069
1403636863051666432 0.086865574 -0.470416307 -0.130248457 -0.030579567 0.073105879 -0.003572948 0.996848881
1403636863101666560 0.086541593 -0.467217296 -0.129189581 -0.025712533 0.075756788 -0.008618753 0.996757507
1403636863151666432 0.091082029 -0.460546255 -0.128123343 -0.023312882 0.076106220 -0.012619973 0.996747255
1403636863201666560 0.091114908 -0.443033338 -0.122930780 -0.022086075 0.078313068 -0.017992087 0.996521771
1403636863251666432 0.089576825 -0.419248223 -0.114035688 -0.023462486 0.079746097 -0.020974457 0.996318281
1403636863301666560 0.093015894 -0.391741335 -0.107074223 -0.025463426 0.080866106 -0.024513425 0.996098101
1403636863351666432 0.095218025 -0.361499965 -0.097539999 -0.027472178 0.081824251 -0.025203085 0.995949209
1403636863401666560 0.097182013 -0.329961360 -0.089015469 -0.029657675 0.085092686 -0.026358934 0.995582640
1403636863451666432 0.096257627 -0.298689544 -0.080433175 -0.032579280 0.087097362 -0.025532512 0.995339513
1403636863501666560 0.099308684 -0.264566362 -0.071025975 -0.037650153 0.087333433 -0.021486850 0.995235443
1403636863551666432 0.097300269 -0.231301382 -0.064786345 -0.043770809 0.083442308 -0.016334543 0.995416820
1403636863601666560 0.097185113 -0.199334472 -0.058727078 -0.051063344 0.079773515 -0.010839951 0.995445251
1403636863651666432 0.097520359 -0.167921767 -0.052934900 -0.058425426 0.076428078 -0.006109563 0.995343089
1403636863701666560 0.098047219 -0.141652927 -0.048163418 -0.065909348 0.073234886 -0.001051132 0.995133936
1403636863751666432 0.098697141 -0.119711712 -0.043694001 -0.073064402 0.072230190 0.003731264 0.994701207
1403636863801666560 0.099637605 -0.104625180 -0.040800594 -0.080163784 0.071205705 0.005972346 0.994217217
1403636863851666432 0.100298434 -0.097524308 -0.041002456 -0.086490251 0.071027622 0.005939289 0.993699789
1403636863901666560 0.101008482 -0.099704809 -0.042758569 -0.091825023 0.069856390 0.005732779 0.993305266
1403636863951666432 0.101298541 -0.110663764 -0.047752626 -0.093928479 0.067253083 0.006078473 0.993286192
1403636864001666560 0.100795507 -0.129653171 -0.054601982 -0.093502849 0.065961413 0.005176102 0.993418157
1403636864051666432 0.099643037 -0.155714765 -0.062213939 -0.090747252 0.064496942 0.003671041 0.993776441
1403636864101666560 0.098789237 -0.186322987 -0.071810335 -0.087075539 0.064756602 -0.001105219 0.994094193
1403636864151666432 0.099488512 -0.221926019 -0.080469057 -0.082958966 0.066755399 -0.004676538 0.994303584
1403636864201666560 0.097565174 -0.256575286 -0.088273272 -0.078722894 0.070020959 -0.007714655 0.994404495
1403636864251666432 0.096112289 -0.292997301 -0.097431019 -0.075816400 0.072162226 -0.009448892 0.994462252
1403636864301666560 0.094120018 -0.326925576 -0.104841277 -0.073407546 0.071592197 -0.009145433 0.994687021
1403636864351666432 0.091544926 -0.357438833 -0.112578146 -0.070481442 0.071258947 -0.008883682 0.994924903
1403636864401666560 0.089469291 -0.386014074 -0.118366972 -0.065369561 0.071626440 -0.006600813 0.995265186
1403636864451666432 0.088452220 -0.412279785 -0.123427592 -0.057050649 0.073574431 -0.005271988 0.995642602
1403636864501666560 0.086768635 -0.436420560 -0.127664432 -0.046308886 0.075199284 -0.002065305 0.996090531
1403636864551666432 0.085256159 -0.452700734 -0.129193857 -0.034428794 0.074502215 0.002567173 0.996623039
1403636864601666560 0.081434101 -0.465102017 -0.131418794 -0.024706122 0.076560415 0.003141341 0.996753871
1403636864651666432 0.080573834 -0.467855394 -0.131223246 -0.018018290 0.077788740 0.001431633 0.996806026
1403636864701666560 0.080881171 -0.460661709 -0.129029408 -0.015875602 0.079697400 -0.003902546 0.996685028
1403636864751666432 0.082409590 -0.446339190 -0.123947166 -0.017407039 0.081159495 -0.008876774 0.996509552
1403636864801666560 0.083865844 -0.426002204 -0.119422965 -0.021182453 0.080959916 -0.010818595 0.996433496
1403636864851666432 0.085034594 -0.401626647 -0.112631470 -0.026115306 0.080834255 -0.011873968 0.996314585
1403636864901666560 0.083991826 -0.374682665 -0.104776539 -0.031098811 0.081977345 -0.011721206 0.996079862
1403636864951666432 0.086121678 -0.346703321 -0.095731601 -0.036867186 0.084179260 -0.012717766 0.995687187
1403636865001666560 0.088150740 -0.316605985 -0.086810820 -0.042782988 0.087511353 -0.013474963 0.995153129
1403636865051666432 0.089742832 -0.286825538 -0.077946223 -0.049381644 0.087856539 -0.014187729 0.994807184
1403636865101666560 0.093742207 -0.257267207 -0.070063263 -0.055603251 0.087054022 -0.011652395 0.994582355
1403636865151666432 0.094382554 -0.230765820 -0.061994705 -0.060247738 0.084581420 -0.003630092 0.994586885
1403636865201666560 0.094169632 -0.206493706 -0.053655528 -0.063997917 0.080225818 0.004825664 0.994708359
1403636865251666432 0.094213523 -0.184765697 -0.047223877 -0.066233121 0.075708531 0.012889485 0.994844317
1403636865301666560 0.093937628 -0.166402951 -0.043581944 -0.067269936 0.072838776 0.018444883 0.994901478
1403636865351666432 0.095096298 -0.152445465 -0.038969502 -0.067800835 0.073061347 0.019914271 0.994820774
1403636865401666560 0.095369555 -0.140722036 -0.035837557 -0.069191821 0.073539168 0.018544322 0.994716287
1403636865451666432 0.095500797 -0.134683833 -0.034811765 -0.072742909 0.074502707 0.014703928 0.994455397
1403636865501666560 0.095728703 -0.133989736 -0.034190122 -0.078494906 0.075754620 0.010294664 0.993978739
1403636865551666432 0.095720649 -0.140544951 -0.036182120 -0.084635340 0.075197928 0.006546583 0.993548810
1403636865601666560 0.094080083 -0.154408753 -0.040146191 -0.089346103 0.074285753 0.004810755 0.993214846
1403636865651666432 0.090949945 -0.174998432 -0.046142053 -0.091027439 0.071883440 0.004145595 0.993241966
1403636865701666560 0.086960562 -0.200748608 -0.054390203 -0.088735700 0.069613010 0.004133071 0.993611038
1403636865751666432 0.083966270 -0.229041412 -0.060763579 -0.083228149 0.068603113 0.004681053 0.994155288
1403636865801666560 0.081008375 -0.259793788 -0.068330631 -0.075799987 0.068089195 0.004605988 0.994784892
1403636865851666432 0.078694232 -0.293023556 -0.076162696 -0.067170262 0.068173148 0.006112592 0.995390952
1403636865901666560 0.077451974 -0.326800466 -0.085886143 -0.057089236 0.067798883 0.006999487 0.996039748
1403636865951666432 0.074598581 -0.361618012 -0.094823748 -0.045206185 0.067562610 0.008659195 0.996652722
1403636866001666560 0.073446803 -0.392947733 -0.101564512 -0.031366773 0.067569576 0.009208643 0.997178853
1403636866051666432 0.071919411 -0.426676422 -0.111477688 -0.017185166 0.069539264 0.009627090 0.997384727
1403636866101666560 0.068005159 -0.452362090 -0.117542475 -0.003865697 0.072583087 0.007837032 0.997324109
1403636866151666432 0.068678945 -0.476350367 -0.125239283 0.006649132 0.074063867 0.005974109 0.997213423
1403636866201666560 0.066364795 -0.492397308 -0.132443562 0.013272732 0.075587258 0.003440606 0.997044921
1403636866251666432 0.065679699 -0.501305044 -0.135966003 0.015773727 0.077393219 0.001317599 0.996874988
1403636866301666560 0.066074334 -0.503653049 -0.136998773 0.014058725 0.079535559 -0.001538739 0.996731699
1403636866351666432 0.067471564 -0.496747285 -0.135154635 0.009618003 0.082736358 -0.003768150 0.996517956
1403636866401666560 0.067214176 -0.484514326 -0.131723925 0.003279406 0.085197747 -0.006405729 0.996338069
1403636866451666432 0.068710126 -0.467878073 -0.125835299 -0.003116283 0.086454593 -0.007623759 0.996221721
1403636866501666560 0.072100729 -0.444258273 -0.117459334 -0.008835641 0.086526677 -0.008874764 0.996170819
1403636866551666432 0.072636679 -0.416155845 -0.111489877 -0.014092797 0.087756172 -0.009460696 0.995997369
1403636866601666560 0.076359920 -0.388081044 -0.101066858 -0.019835779 0.088632017 -0.009329043 0.995823205
1403636866651666432 0.081600823 -0.361766398 -0.092773303 -0.026413165 0.090876482 -0.010352897 0.995458007
1403636866701666560 0.085629694 -0.338875771 -0.088894181 -0.033430073 0.091176040 -0.010346767 0.995219767
1403636866751666432 0.088131763 -0.316913426 -0.085020073 -0.039122723 0.089303263 -0.010946780 0.995175600
1403636866801666560 0.091046803 -0.297170758 -0.083055668 -0.043910597 0.086051494 -0.010288579 0.995269418
1403636866851666432 0.092032418 -0.279330879 -0.082155921 -0.048873164 0.080435768 -0.008026277 0.995528519
1403636866901666560 0.092396297 -0.261757582 -0.081018806 -0.055253748 0.075331777 -0.004006130 0.995618463
1403636866951666432 0.091993503 -0.247058123 -0.079979412 -0.063112222 0.070144124 0.000534535 0.995538235
1403636867001666560 0.093055010 -0.234212995 -0.081364512 -0.070621930 0.067648374 0.003711660 0.995199740
1403636867051666432 0.092237845 -0.225143969 -0.080577016 -0.077461660 0.068221368 0.004798886 0.994646907
1403636867101666560 0.092011042 -0.217960760 -0.082493514 -0.082852572 0.067283839 0.004645253 0.994277000
1403636867151666432 0.090875544 -0.211530417 -0.085694268 -0.085802846 0.065082632 0.006415948 0.994163394
1403636867201666560 0.089682475 -0.208474725 -0.090736575 -0.088614263 0.060184754 0.008050129 0.994213462
1403636867251666432 0.086554565 -0.204085410 -0.095490947 -0.090954795 0.054600149 0.008711150 0.994318962
1403636867301666560 0.086575493 -0.204746693 -0.100558616 -0.093596734 0.049383145 0.008493530 0.994348407
1403636867351666432 0.084004827 -0.204317242 -0.105156131 -0.096771680 0.048292000 0.008594584 0.994097173
1403636867401666560 0.083323993 -0.205140442 -0.108402684 -0.100710243 0.048967950 0.006929135 0.993685842
1403636867451666432 0.082679898 -0.206646711 -0.112869106 -0.105939507 0.049703505 0.006898469 0.993105650
1403636867501666560 0.081417277 -0.208556488 -0.117853448 -0.114067413 0.051427551 0.005491544 0.992125869
1403636867551666432 0.080711007 -0.207401812 -0.122821316 -0.127087802 0.052503798 0.002923570 0.990496576
1403636867601666560 0.079363391 -0.206110597 -0.128303289 -0.145867631 0.053534109 0.001542463 0.987853408
1403636867651666432 0.078978628 -0.204044223 -0.133767620 -0.170315862 0.052789170 0.003240830 0.983969152
1403636867701666560 0.077708088 -0.197694883 -0.139700294 -0.197679281 0.052866388 0.006713257 0.978817105
1403636867751666432 0.077497356 -0.195355386 -0.144815445 -0.229609579 0.052661847 0.008772008 0.971817493
1403636867801666560 0.078163370 -0.190214664 -0.149598539 -0.256301761 0.054735951 0.011690958 0.964974999
1403636867851666432 0.079566479 -0.190270960 -0.153047860 -0.278975844 0.056974567 0.015227392 0.958485544
1403636867901666560 0.079128698 -0.188926190 -0.154800147 -0.291282564 0.058419447 0.018581640 0.954670846
1403636867951666432 0.079832219 -0.190750808 -0.154916197 -0.294840515 0.060462013 0.021052543 0.953399301
1403636868001666560 0.078755617 -0.192600816 -0.155802593 -0.291068286 0.061240554 0.022065043 0.954485178
1403636868051666432 0.077916518 -0.195507795 -0.155500457 -0.284233391 0.062345579 0.022101182 0.956470549
1403636868101666560 0.076959223 -0.197147191 -0.156762928 -0.275194347 0.062192589 0.021434793 0.959135413
1403636868151666432 0.076407969 -0.199015811 -0.157975495 -0.268459350 0.061599679 0.021360476 0.961082101
1403636868201666560 0.075007580 -0.199867219 -0.159863144 -0.265072703 0.060691968 0.021532014 0.962075531
1403636868251666432 0.074183658 -0.199885726 -0.161803931 -0.264278889 0.060021024 0.021512222 0.962336421
1403636868301666560 0.071982637 -0.199514925 -0.164743558 -0.264886498 0.059814077 0.024212878 0.962118089
1403636868351666432 0.069296695 -0.198641270 -0.167623788 -0.267212331 0.059816968 0.026103763 0.961425006
1403636868401666560 0.065224633 -0.197576016 -0.170771658 -0.267602742 0.061041709 0.028051261 0.961184561
1403636868451666432 0.061546709 -0.197265059 -0.173375741 -0.265754938 0.061832223 0.029407486 0.961606085
1403636868501666560 0.057735551 -0.197304308 -0.175827160 -0.261265308 0.064226881 0.028362921 0.962710202
1403636868551666432 0.054279029 -0.198000371 -0.178961962 -0.255208552 0.067181364 0.027714433 0.964151025
1403636868601666560 0.049083553 -0.199645877 -0.181373596 -0.251071721 0.071493983 0.027854739 0.964922667
1403636868651666432 0.047601484 -0.201459020 -0.185061604 -0.249480665 0.071834989 0.029278463 0.965267777
1403636868701666560 0.044510145 -0.202004254 -0.188483894 -0.251071960 0.073364109 0.029395752 0.964736462
1403636868751666432 0.041167084 -0.200845957 -0.192110687 -0.254293770 0.072368026 0.027251691 0.964030564
1403636868801666560 0.039008521 -0.200116336 -0.196105868 -0.258926332 0.070269793 0.025965702 0.962987602
1403636868851666432 0.036965739 -0.198634237 -0.199105605 -0.261524886 0.069773048 0.023048744 0.962395549
1403636868901666560 0.034573521 -0.198143959 -0.200086012 -0.261497289 0.070800111 0.019946918 0.962397337
1403636868951666432 0.032272562 -0.198124364 -0.201178133 -0.258517861 0.070522480 0.019486947 0.963231742
1403636869001666560 0.029837117 -0.199202806 -0.201117098 -0.255535781 0.067966543 0.019537318 0.964209676
1403636869051666432 0.027272299 -0.200033814 -0.201227307 -0.253037512 0.065818295 0.020857528 0.964989603
1403636869101666560 0.025591757 -0.201070353 -0.201546595 -0.251011431 0.062953301 0.021589987 0.965693533
1403636869151666432 0.023062436 -0.200179577 -0.201048374 -0.250032902 0.061615620 0.021312613 0.966039777
1403636869201666560 0.022587236 -0.199331492 -0.201167807 -0.249815509 0.059201729 0.020828594 0.966257513
1403636869251666432 0.021317152 -0.199704215 -0.200558737 -0.250882417 0.058919396 0.020691473 0.966001213
1403636869301666560 0.020672655 -0.198668882 -0.199878961 -0.250832886 0.058631785 0.019648543 0.966053367
1403636869351666432 0.020074299 -0.197757810 -0.198789001 -0.250441819 0.058080159 0.019438976 0.966192365
1403636869401666560 0.021031400 -0.197754771 -0.198452324 -0.250106424 0.056539688 0.019593740 0.966367483
1403636869451666432 0.020778719 -0.197413981 -0.197470084 -0.250172764 0.056696404 0.019321391 0.966346622
1403636869501666560 0.022618176 -0.197680771 -0.196986973 -0.250006229 0.056755107 0.019725177 0.966378152
1403636869551666432 0.026382154 -0.197954834 -0.196098089 -0.250337571 0.056950454 0.019807801 0.966279149
1403636869601666560 0.031910919 -0.197961271 -0.195879847 -0.250474066 0.057323635 0.020523503 0.966206789
1403636869651666432 0.038788624 -0.198319495 -0.194830760 -0.252377510 0.058789931 0.019846031 0.965637326
1403636869701666560 0.049777552 -0.197329491 -0.194865882 -0.253543645 0.060184382 0.020072503 0.965241194
1403636869751666432 0.063523501 -0.198101103 -0.194002762 -0.255373925 0.060991041 0.021340832 0.964680672
1403636869801666560 0.078178376 -0.199416339 -0.192699075 -0.255832016 0.063865028 0.021725254 0.964364707
1403636869851666432 0.095836520 -0.200064927 -0.189498395 -0.253440529 0.067249693 0.022809092 0.964740992
1403636869901666560 0.116769761 -0.205249175 -0.186688438 -0.252204359 0.069697522 0.025686296 0.964818835
1403636869951666432 0.137607008 -0.208431631 -0.184256434 -0.249191001 0.073012091 0.027689829 0.965301156
1403636870001666560 0.159564093 -0.209427550 -0.180503950 -0.245911613 0.077331610 0.029207358 0.965760946
1403636870051666432 0.185110271 -0.212189764 -0.176754937 -0.246277317 0.080376394 0.032987457 0.965297341
1403636870101666560 0.210212484 -0.214286134 -0.173628777 -0.248212561 0.084342316 0.035302673 0.964380920
1403636870151666432 0.236964375 -0.215652332 -0.170694143 -0.250489652 0.087930657 0.036774546 0.963416219
1403636870201666560 0.262478560 -0.218718767 -0.167982891 -0.253650755 0.092281923 0.035699751 0.962221801
1403636870251666432 0.289042175 -0.221026212 -0.165386736 -0.254145294 0.094269894 0.036637601 0.961863279
1403636870301666560 0.314043730 -0.223887473 -0.161747575 -0.252433926 0.097472250 0.037154689 0.961974919
1403636870351666432 0.340434343 -0.226148829 -0.158698231 -0.248216644 0.099924102 0.038406748 0.962771297
1403636870401666560 0.364633590 -0.228435993 -0.156345889 -0.244537503 0.104485773 0.037344202 0.963270247
1403636870451666432 0.390006840 -0.229181603 -0.152909338 -0.242639422 0.107343651 0.035905134 0.963490665
1403636870501666560 0.411493570 -0.230261654 -0.150906309 -0.243866086 0.109047726 0.039950833 0.962830126
1403636870551666432 0.431275874 -0.228836715 -0.149460182 -0.245531499 0.109748580 0.044698972 0.962118268
1403636870601666560 0.447680891 -0.226876915 -0.148561299 -0.249667749 0.115499377 0.043744545 0.960422993
1403636870651666432 0.465907097 -0.225949019 -0.146111950 -0.253338516 0.119432062 0.044109706 0.958962917
1403636870701666560 0.478456676 -0.225422293 -0.145174325 -0.252890617 0.124694496 0.042484332 0.958484530
1403636870751666432 0.490955919 -0.226007909 -0.143097132 -0.249757946 0.125045225 0.043414161 0.959218323
1403636870801666560 0.500127554 -0.225059643 -0.141017467 -0.244050696 0.124484070 0.047859166 0.960547984
1403636870851666432 0.507169545 -0.224399298 -0.138810799 -0.239298150 0.123630010 0.049577739 0.961766064
1403636870901666560 0.512093484 -0.222421259 -0.138388425 -0.233743280 0.123432435 0.049281608 0.963171721
1403636870951666432 0.516502142 -0.221245825 -0.137088001 -0.230320081 0.121223800 0.051300585 0.964170992
1403636871001666560 0.516589344 -0.218462408 -0.136666745 -0.227865830 0.121365651 0.053240228 0.964631021
1403636871051666432 0.517620623 -0.216705292 -0.136000603 -0.230163023 0.119690202 0.057187974 0.964068890
1403636871101666560 0.517418504 -0.214584991 -0.135833651 -0.235397622 0.121501520 0.058488831 0.962499022
1403636871151666432 0.516252160 -0.212648690 -0.135921955 -0.241576403 0.125049040 0.056565188 0.960626841
1403636871201666560 0.513644695 -0.212310523 -0.136211246 -0.245134503 0.127642423 0.057846427 0.959307134
1403636871251666432 0.509199023 -0.213601544 -0.136620015 -0.246446878 0.128606051 0.057470530 0.958864748
1403636871301666560 0.502012730 -0.214935049 -0.137253791 -0.244798928 0.128075689 0.058076248 0.959321260
1403636871351666432 0.492829919 -0.216121107 -0.138070077 -0.243882120 0.127006099 0.056593213 0.959785461
1403636871401666560 0.480797261 -0.217105195 -0.138498530 -0.243883684 0.126397669 0.054257702 0.960000277
1403636871451666432 0.465837508 -0.217707023 -0.139202267 -0.243119955 0.124322012 0.052539747 0.960560381
1403636871501666560 0.448705912 -0.218191028 -0.138825729 -0.242835730 0.123031355 0.052482206 0.960801601
1403636871551666432 0.428268850 -0.218298122 -0.138596714 -0.243079618 0.121841475 0.052065182 0.960914254
1403636871601666560 0.406229675 -0.218638316 -0.138508543 -0.244351789 0.120508574 0.051474631 0.960791469
1403636871651666432 0.383827269 -0.218952417 -0.138113916 -0.245470792 0.116337068 0.053384356 0.960916162
1403636871701666560 0.357383430 -0.220228657 -0.139946088 -0.246485159 0.111777022 0.053641900 0.961183369
1403636871751666432 0.328988522 -0.221264541 -0.139904916 -0.246641666 0.107611738 0.054891180 0.961547971
1403636871801666560 0.301348031 -0.222154260 -0.140339226 -0.247604460 0.103691198 0.054773763 0.961737990
1403636871851666432 0.275615335 -0.220847964 -0.139263451 -0.247405380 0.099366583 0.053180631 0.962334991
1403636871901666560 0.245525271 -0.220851481 -0.137331933 -0.246494606 0.096880578 0.051233668 0.962927639
1403636871951666432 0.216818407 -0.219298095 -0.134617478 -0.243895128 0.091774642 0.051032204 0.964099705
1403636872001666560 0.187434077 -0.219858795 -0.133054182 -0.241078630 0.085222088 0.051759478 0.965369999
1403636872051666432 0.157533348 -0.217997879 -0.129034817 -0.237225756 0.079799920 0.051711831 0.966789424
1403636872101666560 0.128457710 -0.216652483 -0.126562491 -0.234963879 0.074523725 0.050885607 0.967806160
1403636872151666432 0.100573994 -0.213544667 -0.123365194 -0.232771009 0.071562774 0.048879165 0.968662620
1403636872201666560 0.074324787 -0.210547775 -0.122583784 -0.233173564 0.068084732 0.047334697 0.968893170
1403636872251666432 0.049509965 -0.207968444 -0.120344833 -0.236400828 0.063681148 0.045062412 0.968518853
1403636872301666560 0.024694661 -0.204325080 -0.119137958 -0.240257025 0.060197722 0.044314492 0.967826962
1403636872351666432 0.004366571 -0.201902628 -0.118293725 -0.245161012 0.055126749 0.042805929 0.966966808
1403636872401666560 -0.013337439 -0.198876411 -0.117673978 -0.248510733 0.051304650 0.041675322 0.966371298
1403636872451666432 -0.027796082 -0.195818707 -0.116201758 -0.250011295 0.048570074 0.040649891 0.966169178
1403636872501666560 -0.038709864 -0.193089396 -0.115999818 -0.248886570 0.046661075 0.039329931 0.966608167
1403636872551666432 -0.044675894 -0.194810688 -0.114561453 -0.250357360 0.044566903 0.039383162 0.966324985
1403636872601666560 -0.047732383 -0.194960654 -0.115042329 -0.248266861 0.042984709 0.037376758 0.967015445
1403636872651666432 -0.047622152 -0.195879161 -0.115910441 -0.245912924 0.042291157 0.035231840 0.967727780
1403636872701666560 -0.045038857 -0.196848243 -0.116705120 -0.244089812 0.042408340 0.033808772 0.968234837
1403636872751666432 -0.039960507 -0.197922379 -0.117557213 -0.243259266 0.043908473 0.032849949 0.968409956
1403636872801666560 -0.031179221 -0.199103028 -0.117537081 -0.244488239 0.045554087 0.032053772 0.968051076
1403636872851666432 -0.020227298 -0.198066801 -0.118690453 -0.243780121 0.048049785 0.032471567 0.968095064
1403636872901666560 -0.004312382 -0.197783694 -0.117352366 -0.244547427 0.050205216 0.034277610 0.967729807
1403636872951666432 0.015832912 -0.198640436 -0.117282718 -0.245403320 0.052954771 0.035487022 0.967322946
1403636873001666560 0.036494628 -0.199291885 -0.115626872 -0.246126935 0.057538722 0.036196325 0.966850877
1403636873051666432 0.062697999 -0.200607389 -0.115084112 -0.246760935 0.060747873 0.036661062 0.966475427
1403636873101666560 0.088125825 -0.199010760 -0.114154175 -0.244795084 0.064410925 0.037772439 0.966695309
1403636873151666432 0.116970934 -0.200305909 -0.113753602 -0.245663300 0.066929787 0.040324826 0.966200709
1403636873201666560 0.145266593 -0.201660961 -0.112554610 -0.246355399 0.072073154 0.042082880 0.965579331
1403636873251666432 0.175629184 -0.203960255 -0.112614617 -0.247529879 0.075973831 0.044669382 0.964863479
1403636873301666560 0.205905631 -0.205471039 -0.111401744 -0.247846052 0.081276566 0.046606034 0.964258432
1403636873351666432 0.236836210 -0.207932144 -0.111425221 -0.249192730 0.085354626 0.048142515 0.963483155
1403636873401666560 0.269179016 -0.208097488 -0.111224383 -0.248830631 0.087786846 0.050891619 0.963216901
1403636873451666432 0.298786193 -0.207174569 -0.111096516 -0.248547986 0.090990774 0.053694230 0.962840319
1403636873501666560 0.326514959 -0.207857847 -0.112752281 -0.250727981 0.095128238 0.053600390 0.961879909
1403636873551666432 0.355307370 -0.205798090 -0.113144003 -0.251970172 0.099542230 0.055284459 0.961013019
1403636873601666560 0.381037354 -0.204925224 -0.114750274 -0.254916012 0.104234636 0.055744935 0.959711134
1403636873651666432 0.403907806 -0.202812821 -0.115897372 -0.256607324 0.109465763 0.054783840 0.958732843
1403636873701666560 0.423144549 -0.200005293 -0.117241427 -0.257971108 0.114080489 0.056199305 0.957746387
1403636873751666432 0.442395657 -0.198099017 -0.119070143 -0.259880245 0.113845780 0.057730608 0.957166970
1403636873801666560 0.456266463 -0.196923360 -0.120421365 -0.262338430 0.114228137 0.057349339 0.956473470
1403636873851666432 0.467621356 -0.193841234 -0.121722952 -0.261248410 0.114705473 0.059202183 0.956601799
1403636873901666560 0.475600183 -0.192083582 -0.123180732 -0.260643274 0.114999719 0.060328800 0.956661165
1403636873951666432 0.479589671 -0.190921709 -0.122934766 -0.260203719 0.117003135 0.060083460 0.956553340
1403636874001666560 0.483453363 -0.189512417 -0.123160884 -0.259098768 0.117031515 0.061262015 0.956775010
1403636874051666432 0.483372509 -0.188720554 -0.122300670 -0.258829296 0.118494213 0.062006876 0.956619918
1403636874101666560 0.479948729 -0.188501209 -0.120920829 -0.259671569 0.120150834 0.061865464 0.956194103
1403636874151666432 0.476241440 -0.188636497 -0.120287396 -0.260140896 0.119751692 0.061555713 0.956136584
1403636874201666560 0.471070766 -0.188746005 -0.119517885 -0.261140645 0.118279234 0.060866594 0.956091464
1403636874251666432 0.461791992 -0.189121321 -0.119061574 -0.261879444 0.117878988 0.060329225 0.955972850
1403636874301666560 0.449695438 -0.190610036 -0.118576154 -0.264140218 0.114962704 0.058404990 0.955825508
1403636874351666432 0.434526980 -0.190187961 -0.117879950 -0.264074594 0.111030743 0.057899896 0.956339061
1403636874401666560 0.416332096 -0.191560298 -0.115611225 -0.265859157 0.105854094 0.057028897 0.956483901
1403636874451666432 0.393742591 -0.191784084 -0.113282628 -0.265318096 0.102687277 0.056875240 0.956988394
1403636874501666560 0.369796425 -0.191513687 -0.110965766 -0.262888283 0.099313691 0.056155995 0.958056927
1403636874551666432 0.344151258 -0.192299813 -0.108254723 -0.260601997 0.097471878 0.054440405 0.958969295
1403636874601666560 0.316417068 -0.192886055 -0.105974123 -0.259363860 0.094004013 0.052893575 0.959737420
1403636874651666432 0.286784738 -0.191632956 -0.103947774 -0.256830215 0.089513063 0.052025773 0.960894942
1403636874701666560 0.256338269 -0.190836728 -0.102387987 -0.255849928 0.084048189 0.050562151 0.961727679
1403636874751666432 0.225485444 -0.190386236 -0.099266037 -0.256090730 0.080373831 0.049402121 0.962037981
1403636874801666560 0.195952252 -0.187883288 -0.095535815 -0.256300777 0.075793818 0.048631992 0.962392986
1403636874851666432 0.166757733 -0.185249120 -0.092739016 -0.256556958 0.070904285 0.050320044 0.962610543
1403636874901666560 0.139747441 -0.182357609 -0.090865031 -0.257849187 0.065178156 0.050049584 0.962684095
1403636874951666432 0.113428295 -0.182058886 -0.086693048 -0.259833843 0.063479722 0.052075028 0.962156355
1403636875001666560 0.093336403 -0.179084241 -0.084059536 -0.257003129 0.059916973 0.050994515 0.963202417
1403636875051666432 0.074132502 -0.178486884 -0.079192258 -0.252420455 0.061489701 0.051721077 0.964275837
1403636875101666560 0.058835182 -0.177997053 -0.074020982 -0.244451284 0.065586731 0.052307189 0.966025829
1403636875151666432 0.045137677 -0.177101195 -0.068806112 -0.234611034 0.074116208 0.055686798 0.967658758
1403636875201666560 0.032717455 -0.176502168 -0.064410672 -0.225936219 0.083439566 0.058634315 0.968789279
1403636875251666432 0.022887440 -0.175046504 -0.061654817 -0.218351260 0.092776954 0.064931393 0.969277620
1403636875301666560 0.012212170 -0.173006982 -0.059634358 -0.213507414 0.103381373 0.072670572 0.968734145
1403636875351666432 0.002412517 -0.171254531 -0.059790250 -0.210787058 0.112302788 0.083752476 0.967441201
1403636875401666560 -0.006624641 -0.169032723 -0.062904149 -0.211553559 0.119539760 0.093516044 0.965510309
1403636875451666432 -0.015554817 -0.165309384 -0.069610372 -0.211446002 0.125022277 0.103254482 0.963845670
1403636875501666560 -0.021286270 -0.161357701 -0.079598434 -0.214017957 0.128113866 0.111879155 0.961907566
1403636875551666432 -0.026462454 -0.156278059 -0.093103588 -0.215465069 0.131662667 0.120337114 0.960082650
1403636875601666560 -0.027717201 -0.151210368 -0.109347470 -0.217652202 0.133855939 0.126264274 0.958523571
1403636875651666432 -0.026823757 -0.146598637 -0.127603486 -0.218720466 0.138088137 0.131555229 0.956967175
1403636875701666560 -0.021775356 -0.140660807 -0.147000134 -0.218186304 0.143670335 0.134738624 0.955823779
1403636875751666432 -0.014712270 -0.135381103 -0.165484637 -0.216692790 0.152523652 0.137965202 0.954330325
1403636875801666560 -0.005195938 -0.129002586 -0.185461134 -0.216125339 0.161394209 0.140642017 0.952607810
1403636875851666432 0.005289074 -0.122738197 -0.203823656 -0.216441989 0.170890227 0.143965244 0.950380683
1403636875901666560 0.017932802 -0.116160065 -0.223508134 -0.217684343 0.181162998 0.147727117 0.947612882
1403636875951666432 0.031464770 -0.111344993 -0.241952553 -0.218419746 0.193829164 0.151675820 0.944307923
1403636876001666560 0.048571371 -0.107887745 -0.258747935 -0.217373237 0.206944421 0.157070935 0.940878093
1403636876051666432 0.068166345 -0.105719529 -0.274979025 -0.215118945 0.221705809 0.158419922 0.937802494
1403636876101666560 0.088847697 -0.104650050 -0.289817631 -0.210563093 0.237117752 0.160814509 0.934653401
1403636876151666432 0.112436451 -0.105746023 -0.301311016 -0.207119867 0.250409245 0.164247200 0.931353569
1403636876201666560 0.137026355 -0.105955377 -0.309283823 -0.203372240 0.261755556 0.167057768 0.928555608
1403636876251666432 0.162478536 -0.107170105 -0.314239740 -0.202207863 0.272105962 0.170394674 0.925222099
1403636876301666560 0.188516483 -0.107718520 -0.314985543 -0.202264965 0.280381501 0.172845244 0.922279596
1403636876351666432 0.218202978 -0.109303802 -0.313039333 -0.204488710 0.287530899 0.176795557 0.918832779
1403636876401666560 0.247404590 -0.112746783 -0.308391392 -0.208078057 0.293314129 0.179135203 0.915740669
1403636876451666432 0.278951705 -0.113793463 -0.298098117 -0.208024412 0.300707012 0.178427994 0.913490355
1403636876501666560 0.311243206 -0.118013069 -0.286974281 -0.207727849 0.305586576 0.175461873 0.912512541
1403636876551666432 0.342318565 -0.123738728 -0.271910101 -0.204327792 0.308547139 0.172186688 0.912907720
1403636876601666560 0.369662315 -0.130740598 -0.255044311 -0.200255647 0.310395569 0.165027335 0.914504409
1403636876651666432 0.396849900 -0.139492378 -0.234556124 -0.195584849 0.309007168 0.158477977 0.917140007
1403636876701666560 0.419258863 -0.149468899 -0.212805212 -0.191974238 0.304573983 0.152058855 0.920466542
1403636876751666432 0.437219530 -0.159240946 -0.189069390 -0.188852653 0.298090398 0.145800218 0.924239695
1403636876801666560 0.450444639 -0.169319659 -0.163590580 -0.187020555 0.290091842 0.137727052 0.928386390
1403636876851666432 0.457851619 -0.179128483 -0.137786597 -0.185973078 0.280968726 0.129000112 0.932646513
1403636876901666560 0.460175067 -0.188958466 -0.111822233 -0.183927923 0.269112468 0.120169818 0.937714338
1403636876951666432 0.457048774 -0.197107986 -0.084100194 -0.180819705 0.255116940 0.111818217 0.943247736
1403636877001666560 0.446056992 -0.205549359 -0.056657638 -0.178321809 0.241549551 0.104488455 0.948123038
1403636877051666432 0.433608502 -0.211823627 -0.028431777 -0.176717535 0.222848773 0.095697403 0.953913689
1403636877101666560 0.415539622 -0.217662856 -0.003618509 -0.175180510 0.203215331 0.086851150 0.959412396
1403636877151666432 0.391652495 -0.223996043 0.017425247 -0.175339013 0.182726637 0.077073455 0.964327157
1403636877201666560 0.362892717 -0.229144633 0.037637532 -0.175608352 0.160963044 0.068916835 0.968763649
1403636877251666432 0.334021658 -0.232239053 0.057779208 -0.175939977 0.139778122 0.060503069 0.972546399
1403636877301666560 0.301865429 -0.236639172 0.070963450 -0.177140743 0.119791150 0.053885587 0.975380719
1403636877351666432 0.266392320 -0.238524333 0.081416868 -0.178457722 0.100583658 0.045179877 0.977749765
1403636877401666560 0.230423033 -0.239696354 0.086483121 -0.180537432 0.081508085 0.037243728 0.979477167
1403636877451666432 0.195239350 -0.238122433 0.088972315 -0.183112994 0.063125037 0.030877469 0.980577111
1403636877501666560 0.159892425 -0.234557375 0.088883415 -0.186656013 0.046818040 0.025045928 0.980989456
1403636877551666432 0.126918808 -0.230657935 0.085037760 -0.191825777 0.032472968 0.023336722 0.980613947
1403636877601666560 0.096011236 -0.224042043 0.076094061 -0.197497562 0.019629989 0.021436637 0.979872346
1403636877651666432 0.067875616 -0.216426536 0.063951761 -0.202979222 0.009694419 0.020655926 0.978917122
1403636877701666560 0.041866101 -0.208556682 0.049390651 -0.208285764 0.001483745 0.022382731 0.977810740
1403636877751666432 0.018902503 -0.201535195 0.030733641 -0.213602632 -0.003738131 0.024044152 0.976617515
1403636877801666560 -0.001198447 -0.193285406 0.011147276 -0.218369171 -0.004206340 0.026205560 0.975505233
1403636877851666432 -0.017718261 -0.185067564 -0.010257989 -0.223300010 -0.002267059 0.031407095 0.974241018
1403636877901666560 -0.030320259 -0.176205784 -0.032874100 -0.228592977 0.001653744 0.034361992 0.972914040
1403636877951666432 -0.039809853 -0.166375235 -0.053563051 -0.233466670 0.009329141 0.037241738 0.971606553
1403636878001666560 -0.044862680 -0.157536179 -0.076176077 -0.238894522 0.017591730 0.041038804 0.970018446
1403636878051666432 -0.045195919 -0.145871282 -0.100041300 -0.239843532 0.027753841 0.044525482 0.969392717
1403636878101666560 -0.041101217 -0.134270042 -0.119918913 -0.239226893 0.039378863 0.048700877 0.968941689
1403636878151666432 -0.033243828 -0.126318544 -0.142078966 -0.239527494 0.052881762 0.055117030 0.967880249
1403636878201666560 -0.021592461 -0.120637313 -0.161478534 -0.240172312 0.065311030 0.061477508 0.966577590
1403636878251666432 -0.006281551 -0.112739563 -0.179156631 -0.238677025 0.079397127 0.067481242 0.965492427
1403636878301666560 0.010051984 -0.103312388 -0.196866214 -0.233588651 0.092288017 0.075880304 0.964967072
1403636878351666432 0.029791892 -0.099550284 -0.214047074 -0.232141122 0.105626732 0.082980052 0.963362753
1403636878401666560 0.056079414 -0.091330267 -0.227200150 -0.227187291 0.117818795 0.088598184 0.962629199
1403636878451666432 0.084198892 -0.087990530 -0.239762366 -0.225516930 0.129376799 0.096536063 0.960772872
1403636878501666560 0.109981716 -0.087425232 -0.248745337 -0.225034028 0.147155210 0.099505283 0.958020747
1403636878551666432 0.141570270 -0.088267535 -0.256133914 -0.222857878 0.159958541 0.105000094 0.955888391
1403636878601666560 0.172670156 -0.091476157 -0.261474609 -0.221274272 0.173764408 0.107844844 0.953526676
1403636878651666432 0.206174582 -0.096280009 -0.260277510 -0.219236940 0.187331185 0.111303225 0.951027751
1403636878701666560 0.237066627 -0.102388278 -0.259495765 -0.216867119 0.200527668 0.111593619 0.948843598
1403636878751666432 0.268730462 -0.108753495 -0.254849434 -0.213523924 0.211369455 0.109698460 0.947468579
1403636878801666560 0.299976885 -0.115990326 -0.246906877 -0.209587052 0.220109507 0.109884843 0.946335256
1403636878851666432 0.329005301 -0.124609306 -0.239109397 -0.207033485 0.226299897 0.110515125 0.945363402
1403636878901666560 0.356330901 -0.132580698 -0.228447497 -0.205949843 0.229669288 0.111399397 0.944683433
1403636878951666432 0.382853776 -0.140222013 -0.215461031 -0.206158146 0.230592236 0.112719603 0.944256485
1403636879001666560 0.405564129 -0.147733122 -0.202267066 -0.207566455 0.230926111 0.113427036 0.943781555
1403636879051666432 0.425486296 -0.155829862 -0.186400399 -0.207234323 0.230369568 0.114537120 0.943856478
1403636879101666560 0.441640615 -0.165397823 -0.169586107 -0.204323605 0.229557902 0.114275388 0.944720149
1403636879151666432 0.454893947 -0.175557762 -0.149905056 -0.198534846 0.227137968 0.113299653 0.946654856
1403636879201666560 0.464657664 -0.186322242 -0.130147949 -0.191244155 0.224901497 0.110908061 0.948970199
1403636879251666432 0.470550567 -0.196958870 -0.109727859 -0.184529990 0.221831858 0.105744101 0.951607823
1403636879301666560 0.471071482 -0.206989512 -0.089431047 -0.177970409 0.217431009 0.101551242 0.954325736
1403636879351666432 0.469794393 -0.217511117 -0.069489360 -0.173834264 0.209657937 0.095523804 0.957444727
1403636879401666560 0.462446809 -0.226711273 -0.051415972 -0.170044810 0.200521454 0.090156250 0.960597634
1403636879451666432 0.449505270 -0.233859479 -0.033726405 -0.167509869 0.188609272 0.082237132 0.964159787
1403636879501666560 0.433667898 -0.239578575 -0.017175287 -0.165927768 0.175326362 0.074874759 0.967534184
1403636879551666432 0.413997442 -0.245543256 -0.004466150 -0.167083293 0.160787389 0.068326153 0.970341265
1403636879601666560 0.392064214 -0.251136124 0.004875110 -0.167930543 0.146011353 0.063646652 0.972845912
1403636879651666432 0.366591603 -0.255944788 0.013539715 -0.168893591 0.131862849 0.060301002 0.974910736
1403636879701666560 0.338922262 -0.261109412 0.018073292 -0.170334086 0.117468499 0.059084889 0.976573825
1403636879751666432 0.307577372 -0.262579113 0.020808663 -0.171476379 0.104723752 0.056494091 0.977976084
1403636879801666560 0.277402103 -0.263459086 0.021377431 -0.174840346 0.092491567 0.054029182 0.978752792
1403636879851666432 0.246722639 -0.263148814 0.017734766 -0.179054126 0.082714126 0.052469205 0.978950977
1403636879901666560 0.219156295 -0.261482209 0.010001644 -0.184461042 0.074455485 0.051378757 0.978667855
1403636879951666432 0.192658156 -0.257256389 0.000531234 -0.189147934 0.067811728 0.050670177 0.978293002
1403636880001666560 0.167891070 -0.252128482 -0.013141982 -0.193688065 0.063891515 0.048532080 0.977776766
1403636880051666432 0.148539588 -0.246445447 -0.028442368 -0.197488338 0.060259234 0.048230257 0.977262020
1403636880101666560 0.134814098 -0.240675971 -0.046077244 -0.200466588 0.059291925 0.047416147 0.976754487
1403636880151666432 0.126175389 -0.235128820 -0.066292048 -0.201950416 0.060482223 0.047020599 0.976394951
1403636880201666560 0.121761352 -0.228468642 -0.086198360 -0.201703444 0.066591062 0.049154934 0.975943208
1403636880251666432 0.122887075 -0.223138049 -0.108049013 -0.200041205 0.075218827 0.050571278 0.975586057
1403636880301666560 0.129135430 -0.217061460 -0.131277025 -0.197071135 0.085945673 0.053217448 0.975163698
1403636880351666432 0.136482090 -0.212185830 -0.153390273 -0.194846392 0.099524423 0.056918882 0.974109828
1403636880401666560 0.144909889 -0.206337452 -0.176526204 -0.190583676 0.113721922 0.059332080 0.973254800
1403636880451666432 0.150933474 -0.202711686 -0.199126691 -0.187724218 0.129423678 0.061747119 0.971697688
1403636880501666560 0.155221269 -0.199651599 -0.223610759 -0.185309902 0.143044263 0.063782476 0.970118761
1403636880551666432 0.158007681 -0.196198493 -0.246981427 -0.184407070 0.155700579 0.067472607 0.968090296
1403636880601666560 0.155962184 -0.193035334 -0.270155340 -0.185077146 0.165585652 0.069324777 0.966189384
1403636880651666432 0.150805652 -0.189684242 -0.291608751 -0.188039228 0.172746882 0.072449483 0.964132130
1403636880701666560 0.139719427 -0.186815828 -0.312665582 -0.192360803 0.177792862 0.075220734 0.962148070
1403636880751666432 0.126871303 -0.183512241 -0.330100209 -0.196834132 0.180014744 0.077931732 0.960613191
1403636880801666560 0.110716015 -0.179948241 -0.344217956 -0.199611843 0.179088578 0.080403969 0.960009217
1403636880851666432 0.092464171 -0.178401738 -0.354881793 -0.202091172 0.175940305 0.081815809 0.959953308
1403636880901666560 0.071637876 -0.176267117 -0.362607867 -0.201146618 0.170556515 0.081884742 0.961116791
1403636880951666432 0.053212695 -0.175465032 -0.365142047 -0.198630691 0.163653448 0.080509052 0.962954640
1403636881001666560 0.034043550 -0.176372334 -0.364848554 -0.194352478 0.157159343 0.077284753 0.965171039
1403636881051666432 0.015222065 -0.177268252 -0.361312032 -0.188030198 0.150245056 0.073096685 0.967847109
1403636881101666560 -0.002181299 -0.180806011 -0.354741067 -0.182873100 0.141474336 0.068070583 0.970519900
1403636881151666432 -0.019361906 -0.181193858 -0.345546424 -0.176894203 0.130720034 0.062668100 0.973495483
1403636881201666560 -0.036622774 -0.185648650 -0.335282415 -0.173083797 0.118032686 0.058593567 0.976051748
1403636881251666432 -0.050692942 -0.190681577 -0.322147846 -0.171113268 0.104146600 0.054689065 0.978203893
1403636881301666560 -0.060903408 -0.195829093 -0.308004409 -0.169231966 0.091529146 0.048644345 0.980110526
1403636881351666432 -0.065404058 -0.200717360 -0.289832443 -0.168083623 0.080747284 0.042897172 0.981523097
1403636881401666560 -0.069565929 -0.209795266 -0.271828622 -0.168557748 0.073815964 0.038253427 0.982179284
1403636881451666432 -0.066603743 -0.216005564 -0.252319813 -0.166687891 0.067670852 0.031323772 0.983185947
1403636881501666560 -0.059681542 -0.223460406 -0.231306314 -0.164146438 0.063805267 0.025844974 0.984030962
1403636881551666432 -0.048855390 -0.229568213 -0.208126247 -0.160659149 0.061432324 0.017903624 0.984933555
1403636881601666560 -0.034863975 -0.237094998 -0.186817065 -0.157881126 0.059612323 0.012415855 0.985578895
1403636881651666432 -0.016510610 -0.243380219 -0.165032968 -0.156075120 0.056853406 0.005340797 0.986093163
1403636881701666560 0.004745012 -0.248994410 -0.143877059 -0.155400485 0.056092165 0.000332537 0.986257672
1403636881751666432 0.028949562 -0.253544807 -0.122935690 -0.156094119 0.055652190 -0.003835559 0.986165702
1403636881801666560 0.055186290 -0.257619232 -0.102480792 -0.157500267 0.058726259 -0.006115214 0.985752285
1403636881851666432 0.080677234 -0.260752827 -0.085491613 -0.158772260 0.063364916 -0.005082068 0.985266685
1403636881901666560 0.107441746 -0.262847126 -0.068759292 -0.160275057 0.067720115 -0.002098963 0.984744370
1403636881951666432 0.135826096 -0.265968949 -0.057854943 -0.161905631 0.071804106 0.001801074 0.984188735
1403636882001666560 0.163852796 -0.265771717 -0.046484608 -0.162305221 0.076315083 0.006661191 0.983762503
1403636882051666432 0.189517260 -0.263118595 -0.039454881 -0.161273152 0.082390629 0.010614709 0.983407378
1403636882101666560 0.214128241 -0.259737760 -0.036015697 -0.160239667 0.087881304 0.014127801 0.983056724
1403636882151666432 0.237494409 -0.253941417 -0.035031557 -0.158737957 0.092671387 0.016406307 0.982825041
1403636882201666560 0.258015633 -0.245856345 -0.035852600 -0.156536490 0.098788321 0.018130410 0.982552052
1403636882251666432 0.274906009 -0.237648755 -0.041098282 -0.153688669 0.104572818 0.019077234 0.982385039
1403636882301666560 0.286033124 -0.228492171 -0.048107319 -0.150879696 0.108563058 0.019385351 0.982381582
1403636882351666432 0.294127226 -0.218935743 -0.055960044 -0.147836119 0.108749270 0.020534527 0.982800305
1403636882401666560 0.296476960 -0.208014145 -0.063813105 -0.145862684 0.106820889 0.019828431 0.983321011
1403636882451666432 0.294266731 -0.197842568 -0.071402296 -0.143819049 0.102644123 0.021344673 0.984034896
1403636882501666560 0.288926840 -0.188699961 -0.077570654 -0.142402560 0.097582206 0.022081748 0.984739363
1403636882551666432 0.281341076 -0.181099430 -0.080461837 -0.140112415 0.090802826 0.023197565 0.985690236
1403636882601666560 0.273764133 -0.174018934 -0.080027699 -0.135206878 0.084605440 0.022981815 0.986931026
1403636882651666432 0.264003575 -0.169869170 -0.075862177 -0.127652273 0.078476399 0.021967703 0.988465369
1403636882701666560 0.255016863 -0.166433170 -0.070017323 -0.115410142 0.069742970 0.020118071 0.990662217
1403636882751666432 0.246384799 -0.163280100 -0.059287257 -0.100538701 0.058466289 0.018119700 0.993048489
1403636882801666560 0.237715796 -0.159411967 -0.047786910 -0.085314833 0.046822526 0.013958397 0.995155334
1403636882851666432 0.230425879 -0.153880417 -0.034882948 -0.070664383 0.033359602 0.010064645 0.996891320
1403636882901666560 0.223339513 -0.146989554 -0.020373389 -0.059578471 0.021905469 0.005697560 0.997966945
1403636882951666432 0.216493532 -0.139494061 -0.006962746 -0.053154085 0.008906958 0.002521006 0.998543382
1403636883001666560 0.209472552 -0.130339533 0.006127940 -0.051241245 -0.003324253 -0.000637414 0.998680532
1403636883051666432 0.203210741 -0.120841995 0.018284496 -0.051504724 -0.015554654 -0.003313802 0.998546124
1403636883101666560 0.198174313 -0.111819364 0.030863788 -0.051011395 -0.024221638 -0.007883591 0.998373151
1403636883151666432 0.193237081 -0.102553703 0.043286927 -0.048609883 -0.030697631 -0.012997029 0.998261392
1403636883201666560 0.188961491 -0.093820237 0.055541936 -0.044463642 -0.035287209 -0.018909834 0.998208523
1403636883251666432 0.185170263 -0.084998064 0.066334523 -0.039803110 -0.039565504 -0.023177708 0.998154879
1403636883301666560 0.181389287 -0.077658869 0.075624630 -0.036057089 -0.044318970 -0.024360117 0.998069286
1403636883351666432 0.178418547 -0.071016982 0.083986446 -0.033419397 -0.047732867 -0.026040694 0.997961223
1403636883401666560 0.175998747 -0.065336309 0.091070607 -0.031167962 -0.050998904 -0.026251348 0.997866988
1403636883451666432 0.174340233 -0.061080035 0.096818447 -0.028622461 -0.054137427 -0.027192188 0.997752726
1403636883501666560 0.173147172 -0.057669509 0.100953311 -0.023843268 -0.057841070 -0.028221551 0.997641981
1403636883551666432 0.172253326 -0.055027805 0.105407313 -0.018632801 -0.061791293 -0.029802950 0.997470021
1403636883601666560 0.171326861 -0.052557789 0.108709410 -0.013721490 -0.066065960 -0.031965356 0.997208714
1403636883651666432 0.170629293 -0.050531697 0.111323625 -0.010950595 -0.070388153 -0.032913566 0.996916354
1403636883701666560 0.170772210 -0.048212085 0.113626778 -0.009640363 -0.073835008 -0.035846986 0.996579349
1403636883751666432 0.169835180 -0.046960879 0.115949780 -0.010077809 -0.075843558 -0.037852541 0.996349990
1403636883801666560 0.169686899 -0.045737442 0.116686344 -0.010071200 -0.077570856 -0.037991140 0.996211827
1403636883851666432 0.169368476 -0.044306111 0.118410453 -0.009460228 -0.081141017 -0.035101879 0.996039391
1403636883901666560 0.169888169 -0.042500336 0.119648382 -0.008586298 -0.084408239 -0.033865418 0.995818615
1403636883951666432 0.169803143 -0.041382935 0.120884612 -0.008641094 -0.085438535 -0.035073318 0.995688438
1403636884001666560 0.169835240 -0.040357783 0.121985801 -0.004751670 -0.087387316 -0.035986550 0.995512843
1403636884051666432 0.169971392 -0.039940931 0.122557253 -0.001359464 -0.090072691 -0.036420502 0.995268106
1403636884101666560 0.170636863 -0.039987069 0.122379005 0.001400679 -0.092839405 -0.035225891 0.995056808
1403636884151666432 0.171563908 -0.039339360 0.122431338 0.003797231 -0.092476308 -0.037684459 0.994994283
1403636884201666560 0.171826869 -0.039547659 0.122874230 0.006870006 -0.092611223 -0.038974877 0.994915545
1403636884251666432 0.171810165 -0.039571524 0.122424856 0.009995311 -0.092015803 -0.039435055 0.994926155
1403636884301666560 0.171304300 -0.039542273 0.121228322 0.011361436 -0.092114978 -0.039032876 0.994918168
1403636884351666432 0.170884132 -0.039660271 0.121408686 0.011922621 -0.092531197 -0.038389437 0.994898021
1403636884401666560 0.170901775 -0.039684694 0.121284619 0.011859557 -0.092588797 -0.038241133 0.994899154
1403636884451666432 0.171288759 -0.039800722 0.120917335 0.011676171 -0.092455156 -0.038672373 0.994897068
1403636884501666560 0.171215922 -0.039617758 0.121048555 0.011941741 -0.092526160 -0.038348779 0.994899809
1403636884551666432 0.170989975 -0.039678600 0.121004626 0.011864968 -0.092547625 -0.038395382 0.994896948
1403636884601666560 0.170913428 -0.039661143 0.120997369 0.012165490 -0.092636764 -0.038808927 0.994868994
1403636884651666432 0.171017542 -0.039611071 0.121293277 0.011999455 -0.092590570 -0.038535982 0.994885921
1403636884701666560 0.170745879 -0.039671596 0.121205524 0.011792151 -0.092303924 -0.038809843 0.994904339
1403636884751666432 0.170777649 -0.039442394 0.121198416 0.011896838 -0.092486687 -0.038106430 0.994913340
1403636884801666560 0.171175897 -0.039628599 0.120908931 0.011780519 -0.092472978 -0.038480487 0.994901597
1403636884851666432 0.170827210 -0.039533202 0.121184632 0.011950765 -0.092513546 -0.038338851 0.994901299
1403636884901666560 0.171020925 -0.039438277 0.121556796 0.012007352 -0.092352591 -0.038688928 0.994902015
1403636884951666432 0.170860365 -0.039421413 0.121410042 0.011869850 -0.092556916 -0.038291261 0.994900048
1403636885001666560 0.170941442 -0.039495334 0.121440135 0.011832877 -0.092504852 -0.038533587 0.994895995
1403636885051666432 0.170973256 -0.039650321 0.121207424 0.011708874 -0.092612877 -0.038379010 0.994893372
1403636885101666560 0.170869708 -0.039584775 0.121107638 0.011822844 -0.092569634 -0.038458537 0.994892955
1403636885151666432 0.171062350 -0.039527804 0.121313021 0.011833035 -0.092479058 -0.038408902 0.994903147
1403636885201666560 0.170825094 -0.039586108 0.121389486 0.011681021 -0.092493176 -0.038125232 0.994914591
1403636885251666432 0.170964658 -0.039626628 0.121158257 0.011857965 -0.092521407 -0.038353208 0.994901121
1403636885301666560 0.170915797 -0.039572567 0.121163405 0.011736350 -0.092418253 -0.038361132 0.994911849
1403636885351666432 0.170962214 -0.039503798 0.121389441 0.011877608 -0.092564821 -0.038227428 0.994901657
1403636885401666560 0.170943365 -0.039414097 0.121378630 0.012047218 -0.092436358 -0.038400359 0.994904935
1403636885451666432 0.170987636 -0.039537296 0.121187314 0.012053809 -0.092456415 -0.038168322 0.994911909
1403636885501666560 0.170976549 -0.039487593 0.121161163 0.012045232 -0.092509508 -0.038231324 0.994904637
1403636885551666432 0.170977980 -0.039549645 0.121301107 0.011890147 -0.092621669 -0.038075402 0.994902074
1403636885601666560 0.170969442 -0.039492041 0.121265531 0.012018812 -0.092542335 -0.038317278 0.994898617
1403636885651666432 0.171020165 -0.039505038 0.121045396 0.011955260 -0.092446826 -0.038468543 0.994902432
1403636885701666560 0.170871198 -0.039433751 0.121367723 0.011917944 -0.092538975 -0.038185965 0.994905174
1403636885751666432 0.170916334 -0.039494108 0.121242717 0.011977410 -0.092568778 -0.038306005 0.994897068
1403636885801666560 0.170973733 -0.039596155 0.121217996 0.011796736 -0.092613965 -0.038099092 0.994902968
1403636885851666432 0.171026528 -0.039491758 0.121133223 0.012014111 -0.092406183 -0.038615283 0.994899809
1403636885901666560 0.170791000 -0.039512072 0.121274650 0.011818876 -0.092469908 -0.038371015 0.994905651
1403636885951666432 0.171051174 -0.039532434 0.121307924 0.011927917 -0.092597403 -0.038468562 0.994888723
1403636886001666560 0.170903832 -0.039481666 0.121172301 0.011942323 -0.092547610 -0.038277391 0.994900584
1403636886051666432 0.170886591 -0.039556481 0.121281780 0.011939377 -0.092474289 -0.038468994 0.994900048
1403636886101666560 0.170987844 -0.039436288 0.121259272 0.011973537 -0.092477858 -0.038458548 0.994899690
1403636886151666432 0.170933768 -0.039476391 0.121142268 0.011934525 -0.092417449 -0.038217969 0.994915068
1403636886201666560 0.170974791 -0.039377820 0.121135682 0.011919230 -0.092539303 -0.038280550 0.994901478
1403636886251666432 0.170890599 -0.039542496 0.121169887 0.012033518 -0.092484534 -0.038142916 0.994910479
1403636886301666560 0.171031147 -0.039544504 0.121103913 0.011997963 -0.092469521 -0.038327686 0.994905233
1403636886351666432 0.171048477 -0.039629433 0.121136419 0.011999385 -0.092630021 -0.038120445 0.994898260
1403636886401666560 0.171011284 -0.039575581 0.121204391 0.011921934 -0.092520639 -0.038100619 0.994910121
1403636886451666432 0.170976207 -0.039443456 0.121425115 0.012081981 -0.092531115 -0.038032539 0.994909823
1403636886501666560 0.171021000 -0.039646681 0.120963752 0.011831217 -0.092529207 -0.038165670 0.994907916
1403636886551666432 0.170960337 -0.039511256 0.121348694 0.011941982 -0.092536837 -0.038008109 0.994911909
1403636886601666560 0.171013102 -0.039567024 0.121178597 0.011929835 -0.092589147 -0.038042631 0.994905889
1403636886651666432 0.170935377 -0.039517954 0.121267512 0.011990207 -0.092517354 -0.038130995 0.994908452
1403636886701666560 0.170938730 -0.039559953 0.121162772 0.011910277 -0.092424355 -0.038191102 0.994915724
1403636886751666432 0.171010166 -0.039549485 0.121034056 0.011989363 -0.092526004 -0.037991077 0.994912982
1403636886801666560 0.170946702 -0.039538994 0.121292099 0.012008063 -0.092592210 -0.037994068 0.994906485
1403636886851666432 0.170934618 -0.039598189 0.121315069 0.011865791 -0.092486620 -0.038130805 0.994912803
1403636886901666560 0.171071768 -0.039557148 0.121204972 0.011887548 -0.092678361 -0.037964948 0.994901061
1403636886951666432 0.171018913 -0.039573152 0.121101812 0.011932715 -0.092539676 -0.037934016 0.994914591
1403636887001666560 0.171046585 -0.039568994 0.121016413 0.011897735 -0.092464007 -0.037863176 0.994924724
1403636887051666432 0.171008885 -0.039529938 0.121118054 0.012003399 -0.092668697 -0.037839469 0.994905353
1403636887101666560 0.171040639 -0.039545726 0.121110708 0.011944776 -0.092542559 -0.037949815 0.994913578
1403636887151666432 0.170964092 -0.039538827 0.121171281 0.011846474 -0.092450805 -0.037902791 0.994925082
1403636887201666560 0.170987561 -0.039573409 0.121175289 0.011933220 -0.092552833 -0.037822742 0.994917572
1403636887251666432 0.170915350 -0.039576601 0.121136636 0.011908554 -0.092417747 -0.038121868 0.994919002
1403636887301666560 0.171057999 -0.039572045 0.121241748 0.011842006 -0.092436038 -0.038071375 0.994920075
1403636887351666432 0.170973301 -0.039477292 0.121228680 0.012063830 -0.092538111 -0.038046829 0.994908869
1403636887401666560 0.170972139 -0.039497074 0.121309459 0.011983151 -0.092425153 -0.038024455 0.994921148
1403636887451666432 0.170943916 -0.039558232 0.121051207 0.011853104 -0.092469245 -0.038132798 0.994914472
1403636887501666560 0.171049595 -0.039494842 0.121344388 0.011981469 -0.092512138 -0.037971031 0.994915128
1403636887551666432 0.171007633 -0.039534021 0.121107638 0.011926975 -0.092498004 -0.037951536 0.994917810
1403636887601666560 0.170996472 -0.039577633 0.121131152 0.011916437 -0.092542030 -0.037889790 0.994916260
1403636887651666432 0.171027228 -0.039542973 0.121241868 0.011893149 -0.092547677 -0.037984565 0.994912386
1403636887701666560 0.170998365 -0.039537687 0.121030845 0.011930388 -0.092468008 -0.038082201 0.994915605
1403636887751666432 0.170991808 -0.039521318 0.121190757 0.011998871 -0.092603929 -0.037849892 0.994911015
1403636887801666560 0.170941055 -0.039588593 0.121272355 0.011873898 -0.092470221 -0.037925474 0.994922042
1403636887851666432 0.171036005 -0.039520554 0.121353768 0.012087959 -0.092613131 -0.038009919 0.994902968
1403636887901666560 0.170928389 -0.039569527 0.120988302 0.011853612 -0.092473008 -0.038050335 0.994917274
1403636887951666432 0.170936167 -0.039555378 0.121206969 0.011897287 -0.092474304 -0.038080029 0.994915485
1403636888001666560 0.170971349 -0.039530948 0.121289238 0.011878090 -0.092517972 -0.037928086 0.994917512
1403636888051666432 0.170973971 -0.039546177 0.121323779 0.011936681 -0.092596173 -0.037863851 0.994911969
1403636888101666560 0.171045333 -0.039591495 0.121065572 0.011877473 -0.092594974 -0.037832934 0.994913936
1403636888151666432 0.171077013 -0.039566562 0.120965257 0.011903689 -0.092470765 -0.037968859 0.994920015
1403636888201666560 0.171039313 -0.039546113 0.121116914 0.011823214 -0.092608847 -0.037963655 0.994908333
1403636888251666432 0.171060801 -0.039522540 0.121209167 0.011854614 -0.092651598 -0.037831265 0.994908988
1403636888301666560 0.170990661 -0.039578941 0.121193327 0.011910073 -0.092520267 -0.037770264 0.994922876
1403636888351666432 0.171024173 -0.039528970 0.121177495 0.011999259 -0.092566110 -0.037963066 0.994910181
1403636888401666560 0.171075061 -0.039548196 0.121296838 0.011914001 -0.092580847 -0.037980150 0.994909227
1403636888451666432 0.171024293 -0.039525598 0.121190056 0.011906795 -0.092619240 -0.037913825 0.994908273
1403636888501666560 0.171163484 -0.039535433 0.121107399 0.011881301 -0.092598021 -0.038126662 0.994902372
1403636888551666432 0.170872271 -0.039518431 0.121328890 0.011884864 -0.092409275 -0.037902769 0.994928479
1403636888601666560 0.170937702 -0.039648388 0.121176220 0.011826286 -0.092325918 -0.038217895 0.994924843
1403636888651666432 0.170889318 -0.039619468 0.121253885 0.012006461 -0.092313901 -0.037970651 0.994933248
1403636888701666560 0.170804843 -0.039641198 0.120831393 0.012017678 -0.092501201 -0.038422432 0.994898379
1403636888751666432 0.170859292 -0.039564442 0.121130601 0.012188287 -0.092665739 -0.038315009 0.994885147
1403636888801666560 0.170991316 -0.039584693 0.120905749 0.012060163 -0.093132615 -0.037928440 0.994857907
1403636888851666432 0.170816049 -0.039437663 0.120785400 0.011956349 -0.092709087 -0.038316932 0.994883835
1403636888901666560 0.170831949 -0.039462265 0.120943293 0.012005802 -0.092815623 -0.037816320 0.994892478
1403636888951666432 0.170876756 -0.039442908 0.121108115 0.011965166 -0.092707448 -0.038221806 0.994887531
1403636889001666560 0.170686677 -0.039566267 0.120728731 0.011946946 -0.092995226 -0.038244307 0.994860053
1403636889051666432 0.170886755 -0.039587926 0.120986715 0.012058013 -0.092984699 -0.037838981 0.994875193
1403636889101666560 0.170807123 -0.039431632 0.121099442 0.012183224 -0.092553310 -0.037921477 0.994910717
1403636889151666432 0.170732617 -0.039480239 0.121026590 0.012044016 -0.092508011 -0.038074709 0.994910777
1403636889201666560 0.170763463 -0.039466556 0.121198863 0.012183395 -0.092568703 -0.037543509 0.994923651
1403636889251666432 0.170873791 -0.039461587 0.120999262 0.011996761 -0.092448018 -0.037687335 0.994931698
1403636889301666560 0.170831785 -0.039449129 0.121377409 0.011994739 -0.092287883 -0.038039893 0.994933188
1403636889351666432 0.170774087 -0.039536949 0.121339411 0.011954670 -0.092303261 -0.037872169 0.994938612
1403636889401666560 0.170849100 -0.039457690 0.121018380 0.012182924 -0.092689596 -0.037865087 0.994900227
1403636889451666432 0.170826465 -0.039521258 0.121185064 0.012046780 -0.092486821 -0.037926000 0.994918406
1403636889501666560 0.170923814 -0.039546706 0.121010691 0.012059214 -0.092403859 -0.037960529 0.994924664
1403636889551666432 0.170862675 -0.039498124 0.121379256 0.012090067 -0.092346936 -0.038035188 0.994926691
1403636889601666560 0.171076387 -0.039524212 0.121145934 0.012315217 -0.092290789 -0.037832201 0.994936883
1403636889651666432 0.170872152 -0.039608993 0.121066913 0.012097887 -0.092153773 -0.038248211 0.994936347
1403636889701666560 0.171081617 -0.039548241 0.121093273 0.012384540 -0.092270665 -0.038529810 0.994911134
1403636889751666432 0.170866042 -0.039463911 0.121286675 0.012337745 -0.092116252 -0.038343545 0.994933248
1403636889801666560 0.170922816 -0.039561506 0.120734215 0.012166020 -0.092540681 -0.038351521 0.994895637
1403636889851666432 0.171197027 -0.039466001 0.120963618 0.012216110 -0.092405684 -0.038119309 0.994916499
1403636889901666560 0.171011969 -0.039647911 0.121041685 0.012113760 -0.092163235 -0.038097266 0.994941115
1403636889951666432 0.170889363 -0.039561559 0.120871887 0.012079824 -0.092313118 -0.038407397 0.994915664
1403636890001666560 0.170855671 -0.039482996 0.121107057 0.012171476 -0.092247434 -0.038316716 0.994924188
1403636890051666432 0.171100676 -0.039524991 0.120942965 0.012121811 -0.092111290 -0.037994757 0.994949758
1403636890101666560 0.171154797 -0.039634425 0.120898813 0.012370310 -0.091852568 -0.037854236 0.994975924
1403636890151666432 0.170992702 -0.039436292 0.121059760 0.013004953 -0.091872841 -0.038410824 0.994944632
1403636890201666560 0.170917481 -0.039569311 0.121136226 0.012934415 -0.092499837 -0.038242545 0.994893968
1403636890251666432 0.170711398 -0.039441116 0.121128008 0.012841953 -0.092547916 -0.038574018 0.994877875
1403636890301666560 0.170786127 -0.039420653 0.120988466 0.012283545 -0.092819139 -0.038297080 0.994870365
1403636890351666432 0.171017736 -0.039458327 0.121004693 0.012056384 -0.092773892 -0.038045432 0.994887054
1403636890401666560 0.170995295 -0.039494701 0.120859727 0.012326350 -0.092458941 -0.037361942 0.994938910
1403636890451666432 0.171025276 -0.039604530 0.120976940 0.012435921 -0.092101425 -0.037837651 0.994952738
1403636890501666560 0.170972019 -0.039547414 0.121042520 0.012992995 -0.091880776 -0.038255703 0.994950056
1403636890551666432 0.170849055 -0.039566569 0.121565171 0.012959077 -0.092229337 -0.038396686 0.994912803
1403636890601666560 0.170676887 -0.039569501 0.120941378 0.012810295 -0.092405744 -0.038873754 0.994879842
1403636890651666432 0.170873076 -0.039602615 0.120737508 0.012051694 -0.093118273 -0.038287472 0.994845629
1403636890701666560 0.170887023 -0.039429579 0.120791435 0.012112581 -0.092800573 -0.038188893 0.994878352
1403636890751666432 0.170885354 -0.039536688 0.120807648 0.011984373 -0.092268676 -0.037934080 0.994939148
1403636890801666560 0.171059027 -0.039612092 0.120861068 0.012256135 -0.091889061 -0.038169768 0.994961917
1403636890851666432 0.170872286 -0.039421842 0.121155217 0.012990030 -0.091764525 -0.038536247 0.994949996
1403636890901666560 0.170927376 -0.039487809 0.121149912 0.012935831 -0.091963090 -0.038494851 0.994933963
1403636890951666432 0.170799986 -0.039437141 0.121012419 0.012909572 -0.091829121 -0.038693868 0.994938970
1403636891001666560 0.170803398 -0.039463386 0.120895654 0.012950729 -0.092141025 -0.038243856 0.994926989
1403636891051666432 0.170899272 -0.039461948 0.120899320 0.012709501 -0.092318237 -0.038022127 0.994922161
1403636891101666560 0.170808181 -0.039482225 0.120813102 0.012843663 -0.092294097 -0.038247388 0.994914055
1403636891151666432 0.170757160 -0.039429471 0.121263266 0.012986735 -0.092251852 -0.038377769 0.994911075
1403636891201666560 0.170771912 -0.039545551 0.120866120 0.012696669 -0.092078619 -0.038761154 0.994916022
1403636891251666432 0.170700908 -0.039437681 0.120980136 0.012867255 -0.092239805 -0.038415488 0.994912326
1403636891301666560 0.170776740 -0.039429542 0.121021211 0.012823584 -0.092367359 -0.038395740 0.994901776
1403636891351666432 0.170764863 -0.039533097 0.120907806 0.012772989 -0.092293903 -0.038274568 0.994913936
1403636891401666560 0.170899391 -0.039466470 0.120849878 0.012799646 -0.092342511 -0.038274620 0.994909108
1403636891451666432 0.170818359 -0.039463732 0.121004254 0.012796580 -0.092437163 -0.038434971 0.994894147
1403636891501666560 0.170761257 -0.039484911 0.120820329 0.012829070 -0.092314214 -0.038399324 0.994906545
1403636891551666432 0.170905635 -0.039505553 0.121047944 0.012782071 -0.092315890 -0.038507693 0.994902790
1403636891601666560 0.170779750 -0.039429497 0.121267140 0.012687941 -0.092359468 -0.038765039 0.994889975
1403636891651666432 0.170926675 -0.039545257 0.121053554 0.012714823 -0.092564248 -0.038188607 0.994892836
1403636891701666560 0.170744956 -0.039603617 0.120837763 0.012794104 -0.092184708 -0.038542397 0.994913459
1403636891751666432 0.170854837 -0.039392032 0.121177763 0.012808704 -0.092353389 -0.038426176 0.994902134
1403636891801666560 0.170835346 -0.039559271 0.121034853 0.012676742 -0.092442475 -0.038364828 0.994897902
1403636891851666432 0.170833290 -0.039560676 0.121132657 0.012668355 -0.092335053 -0.038289353 0.994910896
1403636891901666560 0.170855507 -0.039585132 0.120816603 0.012760185 -0.092511863 -0.038081609 0.994901240
1403636891951666432 0.170873091 -0.039560359 0.120878600 0.012682063 -0.092516355 -0.038246054 0.994895518
1403636892001666560 0.170859978 -0.039433390 0.121241063 0.012880241 -0.092464380 -0.038209762 0.994899213
1403636892051666432 0.170908421 -0.039521057 0.120873958 0.012901449 -0.092670523 -0.037933540 0.994890332
1403636892101666560 0.170932859 -0.039591238 0.120836608 0.012607884 -0.092443772 -0.038045082 0.994910896
1403636892151666432 0.170837402 -0.039507199 0.120620459 0.012760511 -0.092362568 -0.038301039 0.994906723
1403636892201666560 0.170818552 -0.039504841 0.120761186 0.012786756 -0.092413776 -0.038251124 0.994903505
1403636892251666432 0.170781225 -0.039498795 0.120916463 0.012762222 -0.092452325 -0.038121119 0.994905233
1403636892301666560 0.171225742 -0.039420810 0.120971039 0.012717104 -0.092291258 -0.038574304 0.994903326
1403636892351666432 0.170686498 -0.039350189 0.121177502 0.012862488 -0.092231803 -0.038514320 0.994909286
1403636892401666560 0.170877010 -0.039554697 0.120598659 0.012636391 -0.092095479 -0.038509030 0.994925022
1403636892451666432 0.170805484 -0.039522897 0.121096760 0.012896517 -0.092194043 -0.038612742 0.994908512
1403636892501666560 0.170941919 -0.039543692 0.120924667 0.012797202 -0.092304118 -0.038274128 0.994912684
1403636892551666432 0.170811400 -0.039402064 0.120912008 0.012809608 -0.092149124 -0.038570050 0.994915485
1403636892601666560 0.170753747 -0.039429411 0.121172130 0.012889713 -0.092209846 -0.038519386 0.994910777
1403636892651666432 0.170749590 -0.039402701 0.120909497 0.012890526 -0.092111900 -0.038597465 0.994916797
1403636892701666560 0.170747221 -0.039482314 0.121268988 0.012849760 -0.092095107 -0.038668845 0.994916081
1403636892751666432 0.170822278 -0.039501999 0.120859697 0.012706696 -0.092082560 -0.038745731 0.994916141
1403636892801666560 0.170876667 -0.039461978 0.120987996 0.012836202 -0.092296630 -0.038461659 0.994905651
1403636892851666432 0.170922875 -0.039528213 0.120994911 0.012673369 -0.092405647 -0.038288195 0.994904339
1403636892901666560 0.170817569 -0.039655093 0.120854542 0.012504139 -0.092100643 -0.038911816 0.994910538
1403636892951666432 0.170831978 -0.039467119 0.120925128 0.012718924 -0.092255063 -0.038732186 0.994900525
1403636893001666560 0.170755446 -0.039418295 0.121114120 0.012822203 -0.092340082 -0.038423833 0.994903266
1403636893051666432 0.170849621 -0.039520942 0.121088475 0.012721061 -0.092237256 -0.038627110 0.994906247
1403636893101666560 0.170967236 -0.039604992 0.120796889 0.012777696 -0.092264481 -0.038387667 0.994912267
1403636893151666432 0.170880705 -0.039489843 0.121127263 0.012745881 -0.092318848 -0.038478326 0.994904101
1403636893201666560 0.170868754 -0.039516654 0.120828122 0.012701018 -0.092213705 -0.038649850 0.994907796
1403636893251666432 0.170809552 -0.039519858 0.121069804 0.012691268 -0.092282452 -0.038750455 0.994897604
1403636893301666560 0.170696318 -0.039478544 0.121240914 0.012773790 -0.092178918 -0.038632080 0.994910777
1403636893351666432 0.170846552 -0.039434202 0.121089473 0.012873739 -0.092342652 -0.038479187 0.994900227
1403636893401666560 0.170900673 -0.039641257 0.120886020 0.012579159 -0.092172027 -0.038790990 0.994907677
1403636893451666432 0.170715153 -0.039459158 0.120727405 0.012790044 -0.092245109 -0.038484748 0.994910121
1403636893501666560 0.170898527 -0.039536066 0.120811716 0.012563623 -0.092302516 -0.038634278 0.994901896
1403636893551666432 0.170830369 -0.039572135 0.121094547 0.012635079 -0.092194252 -0.038582344 0.994913042
1403636893601666560 0.170821249 -0.039486580 0.121051043 0.012748267 -0.092088692 -0.038843386 0.994911194
1403636893651666432 0.170971423 -0.039547514 0.121266395 0.012592590 -0.092436180 -0.038478293 0.994895160
1403636893701666560 0.170841724 -0.039651692 0.120778650 0.012704527 -0.092197739 -0.038731452 0.994906008
1403636893751666432 0.170936555 -0.039535861 0.120843649 0.012823417 -0.092273757 -0.038564268 0.994903982
1403636893801666560 0.171037823 -0.039573509 0.120720580 0.012659436 -0.092311859 -0.038764618 0.994894743
1403636893851666432 0.170722261 -0.039519500 0.120837115 0.012554693 -0.092198558 -0.038725242 0.994908094
1403636893901666560 0.170808747 -0.039596476 0.120954208 0.012584744 -0.092276268 -0.038659353 0.994903088
1403636893951666432 0.170819059 -0.039455961 0.120939285 0.013007663 -0.092406951 -0.038078289 0.994907916
1403636894001666560 0.170643896 -0.039342787 0.121204570 0.012838680 -0.092186488 -0.038521565 0.994913518
1403636894051666432 0.170765594 -0.039507225 0.121077076 0.012751829 -0.092416279 -0.038197156 0.994905829
1403636894101666560 0.170817539 -0.039680716 0.120843388 0.012580996 -0.092099361 -0.038790934 0.994914412
1403636894151666432 0.170838282 -0.039507527 0.120917171 0.012766568 -0.092424005 -0.038294084 0.994901180
1403636894201666560 0.170890421 -0.039552573 0.120906651 0.012681970 -0.092378221 -0.038240958 0.994908571
1403636894251666432 0.170838758 -0.039568711 0.120891459 0.012605035 -0.092344075 -0.038522240 0.994901896
1403636894301666560 0.170809805 -0.039480142 0.121108890 0.012771809 -0.092291474 -0.038418371 0.994908631
1403636894351666432 0.170834541 -0.039478905 0.120922439 0.012734587 -0.092274666 -0.038391579 0.994911671
1403636894401666560 0.170859292 -0.039490908 0.121013433 0.012711909 -0.092241578 -0.038544439 0.994909167
1403636894451666432 0.170868963 -0.039607830 0.121025749 0.012610693 -0.092377886 -0.038296744 0.994907379
1403636894501666560 0.170914859 -0.039523602 0.120897874 0.012742721 -0.092487954 -0.038375847 0.994892418
1403636894551666432 0.170844331 -0.039501444 0.120999135 0.012715613 -0.092367575 -0.038516719 0.994898498
1403636894601666560 0.170839563 -0.039433736 0.121219888 0.012717146 -0.092493892 -0.038267683 0.994896352
1403636894651666432 0.170709968 -0.039471481 0.121218041 0.012595001 -0.092273392 -0.038700242 0.994901657
1403636894701666560 0.170839295 -0.039474938 0.121071741 0.012760642 -0.092433915 -0.038444653 0.994894505
1403636894751666432 0.170835659 -0.039506081 0.120734431 0.012759376 -0.092255563 -0.038653579 0.994903028
1403636894801666560 0.170858279 -0.039482050 0.120935269 0.012600246 -0.092503391 -0.038412459 0.994891346
1403636894851666432 0.170754313 -0.039518356 0.120848268 0.012592585 -0.092064746 -0.038616508 0.994924247
1403636894901666560 0.170852169 -0.039373256 0.121213704 0.012811338 -0.092308126 -0.038559429 0.994901121
1403636894951666432 0.170798630 -0.039408412 0.120940626 0.012892966 -0.092408605 -0.037987437 0.994912744
1403636895001666560 0.170974657 -0.039429385 0.120884523 0.012806602 -0.092347354 -0.038456906 0.994901478
1403636895051666432 0.170875132 -0.039488539 0.120794721 0.012751472 -0.092196263 -0.038641501 0.994909108
1403636895101666560 0.170876220 -0.039554801 0.120911494 0.012621425 -0.092115164 -0.038785115 0.994912624
1403636895151666432 0.171014026 -0.039563466 0.120740563 0.012875535 -0.092223808 -0.038299877 0.994918108
1403636895201666560 0.171132952 -0.039478928 0.120645642 0.012932543 -0.092433184 -0.038075760 0.994906545
1403636895251666432 0.170855045 -0.039440744 0.121063992 0.012871601 -0.092065379 -0.038692728 0.994917631
1403636895301666560 0.170839891 -0.039588489 0.120831266 0.012771029 -0.092289180 -0.038221892 0.994916379
1403636895351666432 0.170999780 -0.039498493 0.121050417 0.012785417 -0.092323989 -0.038534742 0.994900942
1403636895401666560 0.170729220 -0.039358824 0.121326998 0.012975473 -0.092350908 -0.038610179 0.994893014
1403636895451666432 0.170910642 -0.039408285 0.120860547 0.012840766 -0.092122279 -0.038692370 0.994912803
1403636895501666560 0.170789376 -0.039400410 0.121196620 0.012740725 -0.092321828 -0.038852170 0.994889379
1403636895551666432 0.170809209 -0.039429832 0.120873347 0.012764203 -0.092210807 -0.038515586 0.994912446
1403636895601666560 0.170782849 -0.039405476 0.121045917 0.012842055 -0.092211939 -0.038582701 0.994908750
1403636895651666432 0.170971021 -0.039489951 0.120905161 0.012849361 -0.092179678 -0.038713250 0.994906545
1403636895701666560 0.170652032 -0.039369192 0.121249914 0.012942422 -0.092166744 -0.038624417 0.994910002
1403636895751666432 0.171014056 -0.039447099 0.120864145 0.012958857 -0.092314474 -0.038278177 0.994909465
1403636895801666560 0.170756981 -0.039466266 0.121029995 0.012858315 -0.092303090 -0.038655706 0.994897246
1403636895851666432 0.171053976 -0.039522767 0.120939821 0.012855324 -0.092429616 -0.038299762 0.994899333
1403636895901666560 0.170769453 -0.039432358 0.121125393 0.012957416 -0.092333391 -0.038595192 0.994895518
1403636895951666432 0.170734957 -0.039433632 0.121169105 0.012893994 -0.092313558 -0.038594857 0.994898200
1403636896001666560 0.170707047 -0.039490815 0.121273711 0.012655312 -0.092276216 -0.038959481 0.994890511
1403636896051666432 0.170937926 -0.039591618 0.120822668 0.012354551 -0.092295870 -0.039006144 0.994890630
1403636896101666560 0.170979321 -0.039603561 0.121251121 0.011860920 -0.092524029 -0.038124148 0.994909644
1403636896151666432 0.171090096 -0.039533861 0.121271849 0.011239298 -0.092473045 -0.038327396 0.994913757
1403636896201666560 0.171137035 -0.039510597 0.121569023 0.010842298 -0.092610553 -0.038107302 0.994913816
1403636896251666432 0.171159655 -0.039552182 0.121481940 0.010695694 -0.092547320 -0.038219161 0.994917035
1403636896301666560 0.171323508 -0.039536476 0.121272430 0.010941445 -0.092480764 -0.038532309 0.994908452
1403636896351666432 0.171163768 -0.039624494 0.121163987 0.011154704 -0.092494063 -0.038434990 0.994908631
1403636896401666560 0.171216756 -0.039556663 0.121592581 0.011522842 -0.092609502 -0.038226020 0.994901717
1403636896451666432 0.171068370 -0.039578121 0.121356063 0.011572726 -0.092551857 -0.038491242 0.994896293
1403636896501666560 0.170939580 -0.039658237 0.121225417 0.011596111 -0.092490219 -0.038714487 0.994893074
1403636896551666432 0.171188980 -0.039536025 0.120791763 0.011759634 -0.092594899 -0.038763236 0.994879544
1403636896601666560 0.171036154 -0.039649628 0.121253781 0.011772454 -0.092534713 -0.038650107 0.994889379
1403636896651666432 0.171116337 -0.039765023 0.121254571 0.011564996 -0.092630915 -0.038744342 0.994879246
1403636896701666560 0.171140581 -0.039625756 0.121205851 0.011285569 -0.092566490 -0.038957871 0.994880080
1403636896751666432 0.171212092 -0.039515171 0.121382192 0.010825508 -0.092655003 -0.038831245 0.994881868
1403636896801666560 0.171382427 -0.039643534 0.121362209 0.010808123 -0.092957579 -0.038658742 0.994860590
1403636896851666432 0.171062559 -0.039620712 0.121350281 0.011131278 -0.092714980 -0.038680576 0.994878829
1403636896901666560 0.171390802 -0.039637361 0.121324658 0.010813260 -0.092920035 -0.038894143 0.994854867
1403636896951666432 0.171235964 -0.039590426 0.121364586 0.010828917 -0.092852555 -0.038957737 0.994858503
1403636897001666560 0.171100020 -0.039760031 0.121061735 0.011703364 -0.093167879 -0.038996890 0.994817555
1403636897051666432 0.171249986 -0.039768688 0.120741054 0.011872774 -0.093831919 -0.039059762 0.994750679
1403636897101666560 0.171243027 -0.039631937 0.120051429 0.011928112 -0.095077328 -0.040279295 0.994583130
1403636897151666432 0.171320751 -0.039433159 0.119109556 0.012078311 -0.097106174 -0.041376509 0.994340241
1403636897201666560 0.171392396 -0.038833443 0.118596919 0.011120728 -0.098199360 -0.041360375 0.994244695
1403636897251666432 0.172107220 -0.038356081 0.117498927 0.010653883 -0.098155461 -0.041319251 0.994255841
1403636897301666560 0.174128845 -0.037873197 0.115632728 0.009869865 -0.096945584 -0.040974416 0.994396925
1403636897351666432 0.176747277 -0.037243940 0.113113105 0.008696765 -0.094639249 -0.040457476 0.994651198
1403636897401666560 0.180938870 -0.035548866 0.109950125 0.005431849 -0.091183960 -0.041644942 0.994948089
1403636897451666432 0.185458139 -0.033974409 0.105829895 0.002211211 -0.087982565 -0.042218797 0.995224476
1403636897501666560 0.190537229 -0.032408603 0.101053044 -0.002193866 -0.083719604 -0.044012971 0.995514452
1403636897551666432 0.195780098 -0.030407581 0.096095636 -0.006916211 -0.079567872 -0.045703471 0.995757163
1403636897601666560 0.202215090 -0.028581617 0.089570083 -0.014332128 -0.076046117 -0.047921650 0.995848894
1403636897651666432 0.208089218 -0.027849182 0.082854405 -0.022117143 -0.072100706 -0.051464155 0.995823145
1403636897701666560 0.215575650 -0.028196277 0.072767600 -0.032018580 -0.068118371 -0.056473672 0.995562851
1403636897751666432 0.222563282 -0.030393539 0.063832700 -0.039541613 -0.065872721 -0.060238924 0.995222867
1403636897801666560 0.229191005 -0.034802169 0.054272078 -0.045948204 -0.064224511 -0.063425913 0.994857371
1403636897851666432 0.234676674 -0.041528340 0.046103105 -0.052325044 -0.062996514 -0.066146895 0.994443655
1403636897901666560 0.239628792 -0.049854636 0.039172634 -0.056344770 -0.062641472 -0.068232685 0.994105458
1403636897951666432 0.243844017 -0.060449786 0.032168951 -0.053545512 -0.063163593 -0.069948800 0.994107842
1403636898001666560 0.247776553 -0.070298925 0.028095126 -0.046771970 -0.064644091 -0.069433764 0.994390488
1403636898051666432 0.250999212 -0.078926802 0.025566880 -0.041102689 -0.066799864 -0.068976752 0.994530320
1403636898101666560 0.253385156 -0.085302345 0.023581155 -0.036305092 -0.068783462 -0.068377458 0.994623184
1403636898151666432 0.255866438 -0.091653153 0.022886714 -0.033503197 -0.070703745 -0.067479298 0.994648218
1403636898201666560 0.257926315 -0.098216675 0.021653468 -0.031358637 -0.072535828 -0.067865014 0.994559944
1403636898251666432 0.259563744 -0.105067551 0.021491382 -0.030591695 -0.074024998 -0.069059305 0.994391918
1403636898301666560 0.260697275 -0.112905204 0.021006761 -0.030243892 -0.075554751 -0.069182374 0.994278908
1403636898351666432 0.261752218 -0.122277707 0.020169461 -0.030610967 -0.077191554 -0.070204630 0.994070292
1403636898401666560 0.262195885 -0.131834880 0.020271808 -0.030165842 -0.079070225 -0.069942720 0.993954718
1403636898451666432 0.262240618 -0.142983183 0.019602481 -0.030842237 -0.081027523 -0.070142396 0.993762195
1403636898501666560 0.261949867 -0.153733283 0.020303663 -0.031354815 -0.083211616 -0.069650255 0.993600309
1403636898551666432 0.261252403 -0.165758982 0.020976484 -0.031341571 -0.084558204 -0.069777347 0.993478060
1403636898601666560 0.260878086 -0.177288100 0.021790359 -0.031852782 -0.085857406 -0.071259946 0.993245125
1403636898651666432 0.260301530 -0.188250124 0.023712270 -0.031805709 -0.087016508 -0.071541943 0.993125498
1403636898701666560 0.258744389 -0.199468553 0.025905166 -0.032756940 -0.087571882 -0.072574049 0.992970824
1403636898751666432 0.257292539 -0.209609270 0.029325418 -0.032891490 -0.088742949 -0.072547235 0.992864430
1403636898801666560 0.255107194 -0.220658720 0.031878572 -0.032836176 -0.090110309 -0.072238602 0.992765546
1403636898851666432 0.252896845 -0.230271503 0.035724938 -0.033527203 -0.091295071 -0.070986100 0.992724597
1403636898901666560 0.250449240 -0.239665523 0.041023009 -0.034384225 -0.092289649 -0.069867551 0.992682636
1403636898951666432 0.247699469 -0.248888433 0.047042631 -0.035248961 -0.093981490 -0.066694088 0.992711902
1403636899001666560 0.246367633 -0.258654386 0.053536825 -0.036470324 -0.095269546 -0.061922446 0.992854059
1403636899051666432 0.243900597 -0.266758353 0.061160691 -0.035789121 -0.093595944 -0.059655845 0.993176758
1403636899101666560 0.244004726 -0.275806755 0.071006477 -0.034347773 -0.090731137 -0.054954287 0.993764579
1403636899151666432 0.244694471 -0.284729183 0.081890747 -0.031999703 -0.085370280 -0.053017400 0.994422972
1403636899201666560 0.244637817 -0.293555945 0.091822736 -0.027852278 -0.077762999 -0.051583070 0.995246887
1403636899251666432 0.246166825 -0.302796960 0.103485785 -0.021823134 -0.069373317 -0.048409309 0.996176481
1403636899301666560 0.249089852 -0.310777098 0.117247246 -0.016333422 -0.059278738 -0.045151573 0.997086048
1403636899351666432 0.252292752 -0.320012271 0.127427757 -0.011013950 -0.047362771 -0.042245913 0.997923195
1403636899401666560 0.257531911 -0.328562170 0.137586117 -0.007399043 -0.034483589 -0.038749468 0.998626351
1403636899451666432 0.261066854 -0.336125255 0.148673221 -0.005537690 -0.022319399 -0.034923710 0.999125361
1403636899501666560 0.267134845 -0.344025970 0.156672686 -0.008259377 -0.013083988 -0.027797559 0.999493837
1403636899551666432 0.271924168 -0.348850667 0.167378873 -0.012411391 -0.004631166 -0.022008942 0.999669969
1403636899601666560 0.277507305 -0.354656905 0.174856067 -0.016557733 0.002341048 -0.017252939 0.999711335
1403636899651666432 0.284120709 -0.360875785 0.181829765 -0.019194817 0.007965352 -0.012751486 0.999702692
1403636899701666560 0.291687369 -0.367074132 0.189165190 -0.021481343 0.012997737 -0.009786445 0.999636829
1403636899751666432 0.300376385 -0.373016328 0.197131112 -0.023904592 0.017716587 -0.008282695 0.999522924
1403636899801666560 0.310094863 -0.377260625 0.205630809 -0.025403729 0.022126714 -0.008830650 0.999393344
1403636899851666432 0.320057273 -0.383120000 0.213102654 -0.026066456 0.026362076 -0.011280552 0.999248862
1403636899901666560 0.329924434 -0.387301147 0.222365052 -0.025532596 0.030028965 -0.014227611 0.999121606
1403636899951666432 0.341631353 -0.390539855 0.232904643 -0.022759620 0.032395255 -0.016312087 0.999082804
1403636900001666560 0.353839576 -0.394324929 0.241962537 -0.019286903 0.034351833 -0.019006258 0.999042869
1403636900051666432 0.364917517 -0.397358775 0.253957719 -0.015239763 0.035305344 -0.019754451 0.999065101
1403636900101666560 0.376502991 -0.402880818 0.261810511 -0.010907853 0.035821781 -0.020891277 0.999080241
1403636900151666432 0.388761342 -0.409242481 0.267666668 -0.006674133 0.035861369 -0.021939646 0.999093652
1403636900201666560 0.399215400 -0.415341944 0.278436929 -0.004480333 0.036007740 -0.023773434 0.999058664
1403636900251666432 0.410779834 -0.423091590 0.285346657 -0.004275667 0.035340276 -0.024781732 0.999058902
1403636900301666560 0.421082258 -0.436310172 0.288134664 -0.005860460 0.034819175 -0.025800660 0.999043345
1403636900351666432 0.431461841 -0.449377954 0.291552782 -0.009725817 0.033369068 -0.025731383 0.999064505
1403636900401666560 0.441992283 -0.462795019 0.292085856 -0.013862962 0.032140486 -0.025873259 0.999052227
1403636900451666432 0.451609641 -0.477423996 0.296379030 -0.018232653 0.030398654 -0.026086403 0.999031007
1403636900501666560 0.462782294 -0.491889268 0.296416134 -0.020937471 0.028702091 -0.027295541 0.998995841
1403636900551666432 0.472531557 -0.503009617 0.298934340 -0.022595897 0.027507978 -0.027182559 0.998996437
1403636900601666560 0.480045408 -0.515273869 0.301328838 -0.024179440 0.025928533 -0.026828500 0.999011159
1403636900651666432 0.493926197 -0.525703430 0.302120715 -0.027554218 0.024419680 -0.027944125 0.998931229
1403636900701666560 0.501244783 -0.534120977 0.309872925 -0.032299645 0.023355039 -0.026222240 0.998861194
1403636900751666432 0.510559797 -0.542320073 0.313598573 -0.037139863 0.021955481 -0.026056884 0.998728991
1403636900801666560 0.523184180 -0.548338294 0.321140796 -0.039295904 0.020048635 -0.023962868 0.998739064
1403636900851666432 0.532545447 -0.555735409 0.327428490 -0.038165700 0.018713005 -0.021618428 0.998862267
1403636900901666560 0.544088304 -0.564104497 0.332291394 -0.036661286 0.016182467 -0.016382637 0.999062419
1403636900951666432 0.556350708 -0.567017078 0.346454799 -0.033370838 0.014463022 -0.013355032 0.999249160
1403636901001666560 0.569644690 -0.571872711 0.357857198 -0.030947350 0.013556645 -0.011350353 0.999364614
1403636901051666432 0.583454192 -0.573464751 0.371017337 -0.029417783 0.012717689 -0.009458735 0.999441564
1403636901101666560 0.599231958 -0.575500131 0.384410053 -0.027945472 0.011525182 -0.006816089 0.999519765
1403636901151666432 0.615014613 -0.578120947 0.395614862 -0.027515007 0.011499905 -0.005770511 0.999538600
1403636901201666560 0.633485556 -0.579750657 0.407741457 -0.026421778 0.011268735 -0.005892207 0.999570012
1403636901251666432 0.653492093 -0.580444276 0.426694125 -0.025778817 0.011949444 -0.007505739 0.999568045
1403636901301666560 0.674873888 -0.586500168 0.438230366 -0.024963429 0.012567940 -0.010270401 0.999556601
1403636901351666432 0.693319857 -0.590017855 0.453127861 -0.024453966 0.013550599 -0.011660452 0.999541104
1403636901401666560 0.714044571 -0.598268092 0.465735376 -0.024232714 0.014644444 -0.013745054 0.999504566
1403636901451666432 0.737910807 -0.607937515 0.476428747 -0.023804022 0.015638648 -0.016906096 0.999451339
1403636901501666560 0.759801924 -0.617753148 0.490293294 -0.023026308 0.016833454 -0.019916061 0.999394715
1403636901551666432 0.783862412 -0.627357304 0.503657341 -0.022749070 0.017784413 -0.022373207 0.999332607
1403636901601666560 0.806331933 -0.639261663 0.513843775 -0.022147652 0.018539995 -0.024007279 0.999294460
1403636901651666432 0.827524900 -0.645499289 0.530548096 -0.020141054 0.019200455 -0.024951646 0.999301314
1403636901701666560 0.854959965 -0.653209269 0.542419732 -0.018929476 0.019031029 -0.024593735 0.999337077
1403636901751666432 0.877480209 -0.658719957 0.557594121 -0.018093433 0.018475769 -0.023100371 0.999398649
1403636901801666560 0.902715623 -0.664722264 0.566125333 -0.018323911 0.018600360 -0.023528220 0.999382138
1403636901851666432 0.924753249 -0.664694905 0.586019874 -0.018151717 0.019086275 -0.024161400 0.999361038
1403636901901666560 0.947847068 -0.664403379 0.601983547 -0.017878750 0.019132581 -0.024676988 0.999352455
1403636901951666432 0.974113643 -0.666068792 0.616234541 -0.018497026 0.019123185 -0.025488084 0.999320984
1403636902001666560 0.997624874 -0.663248777 0.633330345 -0.017807612 0.019074811 -0.026329607 0.999312639
1403636902051666432 1.022907019 -0.664978385 0.645148516 -0.017918546 0.018853877 -0.027472040 0.999284089
1403636902101666560 1.046190023 -0.664743185 0.665141642 -0.016623050 0.018515630 -0.027304208 0.999317408
1403636902151666432 1.070078492 -0.668148041 0.672254086 -0.016987756 0.018629231 -0.028511394 0.999275446
1403636902201666560 1.094380736 -0.669847429 0.688118279 -0.016885672 0.018122731 -0.028197959 0.999295413
1403636902251666432 1.114678383 -0.679132044 0.700028419 -0.017589528 0.018413356 -0.027405489 0.999300003
1403636902301666560 1.137490273 -0.686855316 0.708897948 -0.018155701 0.018375365 -0.025858769 0.999331832
1403636902351666432 1.157507777 -0.685995996 0.728125155 -0.018332690 0.018860219 -0.024705529 0.999348700
1403636902401666560 1.185935855 -0.684526563 0.743946373 -0.018728290 0.019188587 -0.023475165 0.999364793
1403636902451666432 1.210054040 -0.678444564 0.755215287 -0.019319508 0.020377273 -0.023577007 0.999327600
1403636902501666560 1.234172463 -0.674417019 0.770693481 -0.020870965 0.021873066 -0.024985841 0.999230564
1403636902551666432 1.253906608 -0.662475824 0.792671144 -0.019670475 0.024752911 -0.027102444 0.999132514
1403636902601666560 1.281296015 -0.653293729 0.805231571 -0.020461695 0.026733615 -0.029972244 0.998983681
1403636902651666432 1.306274891 -0.645972848 0.822554231 -0.019975862 0.029048944 -0.032886460 0.998837113
1403636902701666560 1.332412720 -0.640091300 0.834468246 -0.018744173 0.030338591 -0.033292774 0.998809218
1403636902751666432 1.359940290 -0.639141917 0.845479250 -0.018150669 0.031208368 -0.033659894 0.998781085
1403636902801666560 1.376765728 -0.635936856 0.865148485 -0.017680367 0.031904794 -0.032404669 0.998808980
1403636902851666432 1.392837048 -0.628533542 0.883476377 -0.015196584 0.032132544 -0.031562164 0.998869538
1403636902901666560 1.420063376 -0.635977805 0.890253425 -0.013588256 0.030382095 -0.031182095 0.998959422
1403636902951666432 1.440951228 -0.643878996 0.900305033 -0.013016051 0.029648818 -0.031636413 0.998974800
1403636903001666560 1.455737233 -0.647534490 0.916203499 -0.014089784 0.029175300 -0.031379290 0.998982310
1403636903051666432 1.476896286 -0.653964221 0.926870763 -0.013778422 0.027905231 -0.030702066 0.999043941
1403636903101666560 1.499365807 -0.666031718 0.931198955 -0.015179024 0.026419206 -0.031057134 0.999053061
1403636903151666432 1.514943004 -0.674099743 0.942463100 -0.015543206 0.025587790 -0.030459110 0.999087572
1403636903201666560 1.535952806 -0.689185858 0.945205808 -0.016403550 0.024086878 -0.030033994 0.999123991
1403636903251666432 1.552165031 -0.702527523 0.956450105 -0.018110000 0.023015751 -0.030838059 0.999095261
1403636903301666560 1.571638346 -0.718969166 0.960679531 -0.019276343 0.022613838 -0.032032993 0.999045014
1403636903351666432 1.587749362 -0.731929600 0.964439809 -0.020194750 0.022339724 -0.032952771 0.999003112
1403636903401666560 1.600330830 -0.748111606 0.973194718 -0.021014420 0.022543330 -0.035342634 0.998899937
1403636903451666432 1.619584322 -0.758346736 0.978054702 -0.021762431 0.022155341 -0.036442760 0.998853087
1403636903501666560 1.639231086 -0.769413412 0.985372543 -0.021458821 0.021544110 -0.036988534 0.998852968
1403636903551666432 1.657782078 -0.779313087 0.993175268 -0.021429211 0.021017428 -0.037294693 0.998853445
1403636903601666560 1.671853900 -0.783562779 1.002869010 -0.022008404 0.020708133 -0.036784507 0.998866200
1403636903651666432 1.688134551 -0.791000366 1.013371110 -0.025041694 0.019986495 -0.035125349 0.998869240
1403636903701666560 1.701910257 -0.795861542 1.020127296 -0.027329210 0.019141397 -0.033178896 0.998892367
1403636903751666432 1.717727065 -0.796682358 1.031299472 -0.029823272 0.018546388 -0.031571776 0.998884261
1403636903801666560 1.737695456 -0.803030252 1.040430427 -0.031801667 0.016792271 -0.028288573 0.998952687
1403636903851666432 1.754148841 -0.803305864 1.052040577 -0.032289326 0.015442567 -0.024455205 0.999059975
1403636903901666560 1.764893889 -0.807256401 1.066470504 -0.031147003 0.015546689 -0.022890100 0.999131739
1403636903951666432 1.786092162 -0.825191200 1.073199511 -0.030694334 0.013687535 -0.021356618 0.999206901
1403636904001666560 1.805000424 -0.835212231 1.083957553 -0.028741589 0.013192226 -0.019853227 0.999302626
1403636904051666432 1.817566514 -0.846398234 1.094877243 -0.026173735 0.013080183 -0.018446246 0.999401629
1403636904101666560 1.840138316 -0.856427133 1.111979604 -0.024315828 0.012446955 -0.015828667 0.999501526
1403636904151666432 1.859309316 -0.873957098 1.120925665 -0.024561310 0.012024500 -0.014544617 0.999520183
1403636904201666560 1.877489924 -0.900487781 1.126582742 -0.024308901 0.011654371 -0.013723133 0.999542356
1403636904251666432 1.898494244 -0.920275569 1.137300134 -0.023446906 0.012337000 -0.014046196 0.999550283
1403636904301666560 1.917710662 -0.937118769 1.146303773 -0.022498744 0.012529496 -0.013026030 0.999583483
1403636904351666432 1.939843774 -0.958234966 1.155955672 -0.021677174 0.013015351 -0.013895866 0.999583721
1403636904401666560 1.954946876 -0.973914087 1.174558043 -0.020647213 0.014799745 -0.014996046 0.999564767
1403636904451666432 1.980514407 -0.992462218 1.181358933 -0.020624343 0.015948663 -0.017901624 0.999499798
1403636904501666560 2.004403114 -1.004038930 1.193998098 -0.020155260 0.016514109 -0.017698571 0.999503791
1403636904551666432 2.031814814 -1.015800834 1.201732039 -0.020013850 0.017619241 -0.019243801 0.999459147
1403636904601666560 2.054623365 -1.027634978 1.213826776 -0.019639028 0.019098625 -0.021311801 0.999397516
1403636904651666432 2.082017422 -1.032877684 1.228153348 -0.019765679 0.020102175 -0.022207199 0.999355853
1403636904701666560 2.100790501 -1.050455570 1.242418170 -0.020269997 0.022476606 -0.024632560 0.999238312
1403636904751666432 2.122730970 -1.059676051 1.254091978 -0.019875003 0.023879886 -0.025636215 0.999188423
1403636904801666560 2.153075218 -1.066359401 1.267913222 -0.019388650 0.025045205 -0.027040059 0.999132454
1403636904851666432 2.175281286 -1.082196236 1.284642339 -0.020434385 0.026538104 -0.028919136 0.999020457
1403636904901666560 2.200691223 -1.090100408 1.291641712 -0.021117693 0.027935145 -0.030586541 0.998918474
1403636904951666432 2.222629309 -1.093065381 1.309805751 -0.020832974 0.029903969 -0.032265898 0.998814642
1403636905001666560 2.249932289 -1.097593665 1.320831180 -0.020165617 0.030760581 -0.032379113 0.998798668
1403636905051666432 2.275485277 -1.103304982 1.335028887 -0.020154925 0.031408966 -0.031713117 0.998800039
1403636905101666560 2.293043137 -1.108683228 1.354742169 -0.019641137 0.033554412 -0.033941828 0.998667240
1403636905151666432 2.323190689 -1.112194657 1.362331271 -0.018337956 0.033970941 -0.033053830 0.998707712
1403636905201666560 2.350255013 -1.123522639 1.372639298 -0.018791217 0.034815557 -0.035100732 0.998600364
1403636905251666432 2.368935347 -1.129807234 1.387427926 -0.019446502 0.036640532 -0.035288181 0.998515904
1403636905301666560 2.389053583 -1.136894464 1.402655244 -0.020153841 0.038288701 -0.036118068 0.998410404
1403636905351666432 2.411309481 -1.145784974 1.410978079 -0.022114482 0.038845461 -0.035278812 0.998377383
1403636905401666560 2.430951834 -1.155106306 1.425277591 -0.024616061 0.039327171 -0.035686489 0.998285472
1403636905451666432 2.453033447 -1.173454762 1.422912598 -0.025369380 0.038590267 -0.037937980 0.998212337
1403636905501666560 2.469851255 -1.188443780 1.437363863 -0.026349407 0.036413163 -0.040221453 0.998179376
1403636905551666432 2.481595516 -1.202517509 1.454697371 -0.026699184 0.034887806 -0.043124586 0.998103321
1403636905601666560 2.502762079 -1.214375854 1.462223768 -0.026672384 0.032537196 -0.045912981 0.998059094
1403636905651666432 2.516533852 -1.227957726 1.473531008 -0.027455959 0.029959243 -0.045803014 0.998123586
1403636905701666560 2.526385307 -1.236991644 1.491416335 -0.028009797 0.027715074 -0.045108121 0.998204648
1403636905751666432 2.540701866 -1.241442919 1.504127622 -0.027189523 0.024956224 -0.043582506 0.998367906
1403636905801666560 2.552432299 -1.250820279 1.522275686 -0.028027810 0.023000276 -0.042452656 0.998440385
1403636905851666432 2.565634966 -1.252636552 1.540712237 -0.028362636 0.020974847 -0.041455574 0.998517454
1403636905901666560 2.577895641 -1.256040335 1.560497999 -0.029463980 0.019365586 -0.040932029 0.998539627
1403636905951666432 2.588407993 -1.255523086 1.578829169 -0.030868109 0.017978763 -0.040009797 0.998560488
1403636906001666560 2.597643137 -1.259974241 1.597474694 -0.033751544 0.017219542 -0.041048646 0.998438418
1403636906051666432 2.614766836 -1.258481026 1.609921932 -0.036104266 0.016522365 -0.042774554 0.998295486
1403636906101666560 2.622597694 -1.261032701 1.631130695 -0.037697177 0.016009223 -0.044019807 0.998190820
1403636906151666432 2.629683971 -1.255565047 1.651253223 -0.037498478 0.015514891 -0.044120330 0.998201668
1403636906201666560 2.638148546 -1.261065841 1.675831914 -0.035975583 0.014981457 -0.044561852 0.998246253
1403636906251666432 2.645139933 -1.269521713 1.699231267 -0.031883541 0.013930213 -0.043893229 0.998430133
1403636906301666560 2.660790205 -1.273233414 1.719880700 -0.026267065 0.011944539 -0.042456321 0.998681545
1403636906351666432 2.663383484 -1.281899691 1.746042848 -0.022241306 0.011098162 -0.039794132 0.998898685
1403636906401666560 2.675482988 -1.293051720 1.761141539 -0.019445101 0.009322138 -0.036077011 0.999116361
1403636906451666432 2.679952621 -1.310168982 1.779431820 -0.018229021 0.007295553 -0.029621724 0.999368310
1403636906501666560 2.685163498 -1.325186610 1.801674843 -0.018221611 0.005411171 -0.023118310 0.999552011
1403636906551666432 2.694424391 -1.330727339 1.822402596 -0.019195642 0.003456162 -0.018010912 0.999647498
1403636906601666560 2.705164194 -1.343767762 1.838106632 -0.022879113 0.002913997 -0.015979063 0.999606252
1403636906651666432 2.716062069 -1.348795652 1.859166622 -0.023378624 0.003388856 -0.016824635 0.999579370
1403636906701666560 2.723471642 -1.360260963 1.880315065 -0.023133662 0.005262102 -0.021497214 0.999487340
1403636906751666432 2.729481220 -1.367332220 1.906314373 -0.022745814 0.007369430 -0.027001489 0.999349415
1403636906801666560 2.744557381 -1.371038437 1.924642801 -0.022884985 0.008495263 -0.031310584 0.999211550
1403636906851666432 2.757232428 -1.375476122 1.944736481 -0.023362797 0.008955450 -0.034503721 0.999091327
1403636906901666560 2.768833399 -1.375160694 1.972591281 -0.023673693 0.008983995 -0.037180755 0.998987675
1403636906951666432 2.777325392 -1.386813641 1.994873047 -0.024610134 0.009088204 -0.040070999 0.998852372
1403636907001666560 2.788342714 -1.391241789 2.014585018 -0.024403043 0.008694461 -0.041888192 0.998786390
1403636907051666432 2.797560930 -1.395983934 2.038135290 -0.024120463 0.007970394 -0.042328462 0.998780727
1403636907101666560 2.810354948 -1.406525731 2.053287029 -0.025338385 0.007544597 -0.042430282 0.998749554
1403636907151666432 2.821251869 -1.413230658 2.077159643 -0.027317289 0.006972817 -0.043870479 0.998639345
1403636907201666560 2.831899881 -1.419616222 2.093579292 -0.030173419 0.006181455 -0.043496497 0.998578668
1403636907251666432 2.840138674 -1.423711181 2.116410971 -0.032814089 0.005328516 -0.042499095 0.998543262
1403636907301666560 2.843012571 -1.429243207 2.142609596 -0.035961561 0.004929343 -0.042609304 0.998432219
1403636907351666432 2.853152037 -1.434415340 2.168704987 -0.036820099 0.003329590 -0.039915226 0.998518884
1403636907401666560 2.862094641 -1.438204169 2.187577963 -0.037505876 0.001463976 -0.036604717 0.998624682
1403636907451666432 2.868859053 -1.447414756 2.218556404 -0.038761184 0.000351210 -0.034365408 0.998657346
1403636907501666560 2.878285885 -1.459447026 2.241421700 -0.038391206 -0.001618491 -0.030474314 0.998796701
1403636907551666432 2.883858442 -1.472677946 2.269908428 -0.039265223 -0.002695225 -0.026462018 0.998874724
1403636907601666560 2.892394781 -1.486500859 2.292336464 -0.038414992 -0.003393601 -0.025646886 0.998926938
1403636907651666432 2.901785612 -1.503253102 2.319549799 -0.038185194 -0.004101148 -0.023604270 0.998983443
1403636907701666560 2.915662289 -1.516530395 2.344741583 -0.037565369 -0.005251553 -0.021307092 0.999053180
1403636907751666432 2.924669027 -1.539836049 2.371760130 -0.037599888 -0.005167083 -0.021165760 0.999055326
1403636907801666560 2.933380365 -1.560552597 2.400573969 -0.037517704 -0.005159984 -0.019724943 0.999087930
1403636907851666432 2.946472645 -1.583444953 2.425965786 -0.037221890 -0.005562795 -0.019406276 0.999103069
1403636907901666560 2.963880777 -1.598312378 2.458637238 -0.035603341 -0.005897239 -0.019754408 0.999153316
1403636907951666432 2.975321770 -1.607510924 2.485669851 -0.031618088 -0.005233249 -0.022588916 0.999231040
1403636908001666560 2.989616871 -1.618280411 2.522272348 -0.028676214 -0.003907261 -0.027289953 0.999208510
1403636908051666432 3.011894703 -1.631585360 2.555233479 -0.026464632 -0.003638335 -0.033050973 0.999096632
1403636908101666560 3.023734093 -1.640666127 2.588817835 -0.023736825 -0.003387701 -0.035576779 0.999079227
1403636908151666432 3.044673681 -1.652523994 2.619572401 -0.022480048 -0.004351332 -0.037577242 0.999031365
1403636908201666560 3.054709673 -1.664311647 2.652040720 -0.019980457 -0.004599201 -0.038895443 0.999032915
1403636908251666432 3.072110176 -1.677913189 2.683386087 -0.019280873 -0.005457019 -0.040698182 0.998970509
1403636908301666560 3.087620020 -1.690553665 2.714318991 -0.018668728 -0.006357835 -0.041436695 0.998946488
1403636908351666432 3.101723194 -1.704511762 2.744445562 -0.019899247 -0.007114531 -0.042882726 0.998856604
1403636908401666560 3.118743658 -1.714169621 2.775074482 -0.020168666 -0.008595718 -0.042474881 0.998856962
1403636908451666432 3.130422831 -1.727979302 2.807919741 -0.022160402 -0.009280405 -0.043204132 0.998777390
1403636908501666560 3.150338888 -1.730605364 2.838773012 -0.022393879 -0.010861262 -0.042915720 0.998768687
1403636908551666432 3.164500237 -1.735571742 2.869899750 -0.022629246 -0.011788230 -0.042744711 0.998760164
1403636908601666560 3.176381826 -1.744745135 2.904155016 -0.023552027 -0.012579391 -0.043514796 0.998695910
1403636908651666432 3.191662073 -1.752313256 2.936817408 -0.024196686 -0.013675248 -0.044444159 0.998625159
1403636908701666560 3.210622787 -1.760180950 2.962628365 -0.025921006 -0.015127452 -0.043861825 0.998586714
1403636908751666432 3.220979929 -1.772136450 2.998176336 -0.028550902 -0.015694566 -0.043252885 0.998532772
1403636908801666560 3.235084057 -1.786062360 3.025922298 -0.030563692 -0.016950268 -0.042260051 0.998495162
1403636908851666432 3.251398563 -1.805396914 3.054396152 -0.034221105 -0.018355951 -0.040455911 0.998426437
1403636908901666560 3.261879444 -1.821600795 3.086815596 -0.036114234 -0.017994549 -0.040806178 0.998352051
1403636908951666432 3.274778843 -1.842235208 3.116952896 -0.037435707 -0.018821701 -0.040010076 0.998320341
1403636909001666560 3.287699223 -1.865581393 3.149973392 -0.037955735 -0.019210918 -0.039029650 0.998332143
1403636909051666432 3.301355124 -1.883992672 3.179223776 -0.037063845 -0.020005796 -0.037173115 0.998420894
1403636909101666560 3.314195395 -1.907312155 3.209164143 -0.038032830 -0.020266721 -0.035765078 0.998430550
1403636909151666432 3.323643923 -1.927049756 3.242166281 -0.037529565 -0.020248508 -0.034212753 0.998504400
1403636909201666560 3.338638783 -1.945320845 3.279861927 -0.038167041 -0.019871950 -0.035026934 0.998459578
1403636909251666432 3.356090784 -1.964161396 3.313907862 -0.038746584 -0.019799525 -0.034800954 0.998446584
1403636909301666560 3.374808311 -1.982860446 3.347994566 -0.039305497 -0.019921271 -0.034258883 0.998441041
1403636909351666432 3.389549255 -1.998040676 3.387055159 -0.037681814 -0.019202357 -0.034312397 0.998515904
1403636909401666560 3.404039860 -2.010597229 3.425446033 -0.036324661 -0.018489411 -0.035040926 0.998554349
1403636909451666432 3.422705650 -2.026679277 3.462055922 -0.033864748 -0.017504873 -0.036820624 0.998594522
1403636909501666560 3.439044714 -2.040971279 3.503710270 -0.031284347 -0.016394123 -0.038043469 0.998651683
1403636909551666432 3.456240892 -2.051448822 3.545205355 -0.029853687 -0.016033854 -0.037776772 0.998711467
1403636909601666560 3.470221996 -2.062856674 3.587419033 -0.029043468 -0.015320003 -0.036714699 0.998786151
1403636909651666432 3.490094662 -2.071372032 3.628633261 -0.027378907 -0.016272288 -0.032715145 0.998957157
1403636909701666560 3.506899118 -2.079995632 3.670132875 -0.024898920 -0.015900584 -0.031344190 0.999071956
1403636909751666432 3.526634693 -2.086310148 3.711392879 -0.020166712 -0.015327782 -0.032295719 0.999157310
1403636909801666560 3.545388222 -2.090708733 3.755625963 -0.016412867 -0.013601638 -0.036616992 0.999101996
1403636909851666432 3.563436508 -2.092517376 3.800291061 -0.012413692 -0.010656863 -0.043651715 0.998912811
1403636909901666560 3.580898523 -2.094416142 3.840769291 -0.010442500 -0.007581880 -0.051577337 0.998585641
1403636909951666432 3.600157738 -2.095031261 3.884741068 -0.006842826 -0.004781798 -0.059762448 0.998177707
1403636910001666560 3.616197586 -2.092453718 3.927148819 -0.002478542 -0.002593291 -0.064796604 0.997892022
1403636910051666432 3.632784367 -2.092816114 3.969532728 -0.000357942 -0.002267581 -0.067054793 0.997746646
1403636910101666560 3.647514343 -2.094361544 4.003424644 -0.001256960 -0.003611402 -0.064108647 0.997935593
1403636910151666432 3.659368992 -2.092963696 4.043295860 -0.003685059 -0.005446153 -0.059628177 0.998198986
1403636910201666560 3.669453144 -2.096519709 4.079859257 -0.009172816 -0.007433997 -0.054029431 0.998469532
1403636910251666432 3.682228804 -2.098546982 4.114298344 -0.012600591 -0.008808208 -0.051159129 0.998572230
1403636910301666560 3.690123320 -2.102904320 4.146417141 -0.015777940 -0.009912294 -0.048092309 0.998669088
1403636910351666432 3.699009418 -2.106474400 4.183468342 -0.018780969 -0.010884421 -0.046029780 0.998704195
1403636910401666560 3.706773758 -2.113334417 4.215036392 -0.020192709 -0.011676120 -0.045343988 0.998699069
1403636910451666432 3.718419313 -2.125998020 4.245618820 -0.021701397 -0.012455028 -0.046555925 0.998602271
1403636910501666560 3.725349188 -2.136235237 4.276777744 -0.021930221 -0.013346919 -0.046158243 0.998604178
1403636910551666432 3.734834433 -2.148047686 4.306645870 -0.022933951 -0.013579711 -0.047413733 0.998519659
1403636910601666560 3.742676735 -2.157021523 4.338322639 -0.022845285 -0.013681653 -0.048118759 0.998486578
1403636910651666432 3.749779463 -2.165841579 4.370025635 -0.023362581 -0.013740359 -0.048617981 0.998449624
1403636910701666560 3.758669853 -2.170837164 4.401112556 -0.022911865 -0.014278618 -0.048401274 0.998463035
1403636910751666432 3.766246796 -2.178044319 4.434081078 -0.023547428 -0.014748005 -0.047962759 0.998462617
1403636910801666560 3.773153305 -2.184393406 4.466372490 -0.024307383 -0.014913497 -0.047240797 0.998476386
1403636910851666432 3.780040741 -2.184254169 4.499454498 -0.024314515 -0.015518607 -0.046006948 0.998524547
1403636910901666560 3.789905787 -2.185906887 4.533386230 -0.024586260 -0.016608924 -0.043930139 0.998593926
1403636910951666432 3.795734882 -2.189929247 4.559355736 -0.021980163 -0.017179636 -0.042159989 0.998721361
1403636911001666560 3.800795078 -2.189756393 4.603195190 -0.013865788 -0.018638736 -0.038575381 0.998985589
1403636911051666432 3.807497263 -2.195137262 4.636205196 -0.006034537 -0.019262664 -0.037324525 0.999099314
1403636911101666560 3.814653635 -2.200994968 4.668864250 -0.001477883 -0.019576771 -0.037213370 0.999114454
1403636911151666432 3.823156595 -2.207937241 4.695893764 -0.003318608 -0.019635541 -0.037652351 0.999092460
1403636911201666560 3.830921650 -2.213881731 4.726007462 -0.007561916 -0.018574305 -0.039969850 0.998999596
1403636911251666432 3.839225769 -2.221031427 4.756853104 -0.013150885 -0.018354306 -0.040923856 0.998907089
1403636911301666560 3.846101999 -2.230534554 4.778686047 -0.016950179 -0.017359721 -0.042392567 0.998806417
1403636911351666432 3.852818966 -2.242917776 4.805510521 -0.019747693 -0.015970962 -0.045078784 0.998660505
1403636911401666560 3.860385656 -2.257769346 4.830929756 -0.019885238 -0.015883463 -0.045410775 0.998644173
1403636911451666432 3.871901751 -2.271608353 4.850777626 -0.019857476 -0.015596598 -0.046505541 0.998598814
1403636911501666560 3.877647400 -2.289117098 4.874552727 -0.020997392 -0.015227183 -0.046981368 0.998558939
1403636911551666432 3.884654522 -2.302735806 4.901709557 -0.020842351 -0.014904589 -0.046925452 0.998569727
1403636911601666560 3.892154932 -2.319229364 4.924863338 -0.021658635 -0.014925592 -0.047171447 0.998540401
1403636911651666432 3.896323442 -2.329890251 4.951208591 -0.021023901 -0.014311381 -0.047593623 0.998542964
1403636911701666560 3.905895948 -2.345107794 4.971923828 -0.021652242 -0.014727758 -0.046922524 0.998555243
1403636911751666432 3.911327362 -2.354349375 4.997148991 -0.021245340 -0.014788533 -0.045568205 0.998625755
1403636911801666560 3.918906450 -2.362411261 5.024147511 -0.021524142 -0.016108314 -0.041793320 0.998764515
1403636911851666432 3.927153111 -2.372242689 5.047322750 -0.022133552 -0.017462004 -0.038243160 0.998870671
1403636911901666560 3.932338715 -2.378824711 5.073678017 -0.025143448 -0.018632874 -0.032551892 0.998979986
1403636911951666432 3.936991692 -2.383466959 5.104741096 -0.027249601 -0.019235667 -0.027855091 0.999055326
1403636912001666560 3.944544077 -2.384657383 5.130284786 -0.027653072 -0.018686377 -0.028035183 0.999049604
1403636912051666432 3.953894138 -2.384665489 5.156109810 -0.027104793 -0.017428927 -0.029792212 0.999036551
1403636912101666560 3.964917421 -2.390754700 5.185193062 -0.027792810 -0.017280366 -0.029881272 0.999017537
1403636912151666432 3.971089840 -2.392769337 5.218316078 -0.026360318 -0.016565500 -0.031219041 0.999027550
1403636912201666560 3.983577251 -2.399017096 5.244758129 -0.025435882 -0.015853891 -0.033249833 0.998997569
1403636912251666432 3.994964123 -2.405933857 5.273604393 -0.023930296 -0.015240180 -0.034943435 0.998986483
1403636912301666560 4.005242825 -2.413345575 5.297373295 -0.022408940 -0.014425422 -0.037771437 0.998930931
1403636912351666432 4.015815735 -2.423662186 5.329381466 -0.022411281 -0.013422678 -0.038370386 0.998922050
1403636912401666560 4.029271126 -2.436835766 5.356359959 -0.022851544 -0.013269482 -0.038400780 0.998912930
1403636912451666432 4.039226055 -2.444631577 5.375802994 -0.022309382 -0.014020120 -0.035386704 0.999026299
1403636912501666560 4.050056458 -2.452481747 5.404559135 -0.022386238 -0.014991133 -0.031777639 0.999131739
1403636912551666432 4.060459614 -2.462657213 5.435583591 -0.022671554 -0.014230593 -0.031603299 0.999141991
1403636912601666560 4.073868275 -2.468974352 5.462145329 -0.023151658 -0.014353212 -0.029745214 0.999186218
1403636912651666432 4.086198330 -2.474574089 5.496412754 -0.022426208 -0.014919735 -0.026675951 0.999281168
1403636912701666560 4.101340771 -2.481036186 5.527536869 -0.023714155 -0.015691247 -0.023554953 0.999318063
1403636912751666432 4.115419388 -2.483570337 5.555831432 -0.023149289 -0.016645605 -0.019918004 0.999394953
1403636912801666560 4.127438068 -2.481198788 5.584688663 -0.022148553 -0.016580520 -0.018012747 0.999454916
1403636912851666432 4.142179489 -2.481652737 5.612381458 -0.021829421 -0.016087795 -0.018490497 0.999461234
1403636912901666560 4.161889076 -2.477792501 5.649827480 -0.020426033 -0.015004089 -0.021526013 0.999446988
1403636912951666432 4.182066441 -2.481184483 5.677017689 -0.018087339 -0.014217069 -0.024194140 0.999442518
1403636913001666560 4.195953369 -2.479422331 5.706759453 -0.015070571 -0.012434014 -0.028464373 0.999403834
1403636913051666432 4.219180107 -2.476738691 5.736782074 -0.012413672 -0.011685899 -0.031314652 0.999364138
1403636913101666560 4.240725040 -2.476470947 5.768712044 -0.010380506 -0.011189789 -0.033750258 0.999313712
1403636913151666432 4.256749630 -2.472868919 5.792450905 -0.008380010 -0.010209703 -0.035838298 0.999270320
1403636913201666560 4.277938366 -2.476791859 5.829153061 -0.006439592 -0.009789404 -0.037400644 0.999231637
1403636913251666432 4.300932407 -2.475633144 5.854506969 -0.006520068 -0.009779979 -0.037960954 0.999210119
1403636913301666560 4.316480637 -2.474103928 5.879039288 -0.006795503 -0.009282755 -0.038428035 0.999195158
1403636913351666432 4.340419769 -2.484498501 5.903885841 -0.010763615 -0.010537283 -0.036519513 0.999219418
1403636913401666560 4.356007099 -2.490610123 5.927956104 -0.013338961 -0.011194835 -0.034130402 0.999265671
1403636913451666432 4.379843712 -2.496317863 5.950728893 -0.015845453 -0.012851361 -0.029972717 0.999342501
1403636913501666560 4.400728226 -2.505330801 5.972005367 -0.017714832 -0.012917056 -0.028768657 0.999345601
1403636913551666432 4.422379017 -2.509177446 5.987304211 -0.017616473 -0.012327031 -0.030330291 0.999308646
1403636913601666560 4.442421913 -2.517744303 6.012776852 -0.018588554 -0.011381510 -0.032528095 0.999233127
1403636913651666432 4.465777874 -2.521123886 6.034659386 -0.019192545 -0.010561135 -0.033454701 0.999200106
1403636913701666560 4.488696098 -2.526923895 6.057753086 -0.019442445 -0.009683636 -0.034984361 0.999151766
1403636913751666432 4.509930611 -2.526253223 6.078919411 -0.018434158 -0.008931659 -0.036160626 0.999136031
1403636913801666560 4.531915665 -2.526746273 6.100126266 -0.018119844 -0.008859852 -0.036277939 0.999138176
1403636913851666432 4.556265354 -2.529794216 6.116325378 -0.017894808 -0.008426427 -0.037566151 0.999098361
1403636913901666560 4.576528549 -2.537333965 6.142951488 -0.017506361 -0.008254618 -0.037767217 0.999099135
1403636913951666432 4.597400188 -2.546632290 6.162238598 -0.017093027 -0.008163010 -0.038935933 0.999062121
1403636914001666560 4.619834900 -2.551032066 6.178056717 -0.016625972 -0.008245796 -0.039323211 0.999054193
1403636914051666432 4.642180443 -2.558688402 6.195351601 -0.016735271 -0.008746646 -0.038306631 0.999087632
1403636914101666560 4.662306309 -2.570002317 6.216869354 -0.016054081 -0.009541960 -0.035893176 0.999181151
1403636914151666432 4.684339523 -2.580605268 6.236903667 -0.016221998 -0.010066410 -0.033561405 0.999254286
1403636914201666560 4.702710152 -2.592747211 6.258795738 -0.016751105 -0.009421903 -0.032907851 0.999273598
1403636914251666432 4.732018471 -2.601738214 6.274650574 -0.016579010 -0.009874236 -0.033348218 0.999257505
1403636914301666560 4.753945351 -2.603395462 6.290563583 -0.017535686 -0.009189650 -0.034761515 0.999199510
1403636914351666432 4.774385452 -2.609986067 6.308190346 -0.016559694 -0.008503025 -0.035668045 0.999190331
1403636914401666560 4.798665047 -2.617023230 6.328555584 -0.016535936 -0.007525196 -0.038628083 0.999088466
1403636914451666432 4.821258545 -2.620703936 6.344445705 -0.016122954 -0.007174032 -0.039688244 0.999056280
1403636914501666560 4.839195728 -2.629006624 6.363401413 -0.016120149 -0.005799615 -0.041468084 0.998992920
1403636914551666432 4.865205288 -2.640733719 6.383298874 -0.016551945 -0.005832872 -0.042194437 0.998955250
1403636914601666560 4.880168438 -2.650011778 6.401378155 -0.016053874 -0.005038657 -0.042167187 0.998968840
1403636914651666432 4.909172535 -2.662193060 6.413729668 -0.014375654 -0.005229396 -0.043591332 0.998932362
1403636914701666560 4.929146290 -2.677119732 6.427824020 -0.014064349 -0.005270670 -0.043081146 0.998958707
1403636914751666432 4.949183464 -2.692291975 6.444962978 -0.013709951 -0.004277567 -0.043425087 0.998953462
1403636914801666560 4.969641685 -2.707101822 6.455476284 -0.013197825 -0.004097694 -0.043870244 0.998941660
1403636914851666432 4.988485336 -2.718308687 6.466036320 -0.013515837 -0.003768658 -0.044164393 0.998925745
1403636914901666560 5.007790089 -2.725071430 6.479777336 -0.014341356 -0.003230792 -0.043739792 0.998934805
1403636914951666432 5.029036522 -2.735301018 6.492089272 -0.016180836 -0.002538372 -0.044012088 0.998896718
1403636915001666560 5.045947552 -2.740396023 6.504259586 -0.017953184 -0.001985995 -0.043750715 0.998879194
1403636915051666432 5.063479424 -2.747797489 6.520869732 -0.019877087 -0.001543649 -0.043997522 0.998832703
1403636915101666560 5.081306458 -2.754466295 6.533803940 -0.021144863 -0.000851693 -0.044692528 0.998776615
1403636915151666432 5.098575592 -2.755299330 6.551538944 -0.022540566 -0.000163937 -0.044053771 0.998774827
1403636915201666560 5.121088028 -2.757368088 6.560506821 -0.025033265 -0.000314431 -0.044065986 0.998714864
1403636915251666432 5.136790752 -2.761672020 6.580130577 -0.029590292 0.000346342 -0.043770920 0.998603225
1403636915301666560 5.155066490 -2.761446238 6.596460819 -0.034019526 0.000885914 -0.043824419 0.998459518
1403636915351666432 5.172219276 -2.761114597 6.615762711 -0.038511124 0.001075009 -0.044514231 0.998265624
1403636915401666560 5.188225269 -2.759510040 6.634996414 -0.040365189 0.001112259 -0.045434412 0.998150826
1403636915451666432 5.203018188 -2.759756088 6.655999660 -0.040573884 0.000855763 -0.044426229 0.998188019
1403636915501666560 5.215608120 -2.762577295 6.677091599 -0.037420984 0.000148255 -0.040968776 0.998459458
1403636915551666432 5.233282566 -2.765683889 6.694629192 -0.031439919 -0.002017044 -0.036566492 0.998834491
1403636915601666560 5.245903969 -2.771224976 6.715906143 -0.026830478 -0.003656905 -0.031483136 0.999137461
1403636915651666432 5.262118816 -2.780136347 6.735182285 -0.022819657 -0.005930235 -0.026620008 0.999367535
1403636915701666560 5.279909611 -2.789562464 6.750593185 -0.019779569 -0.007787557 -0.022947086 0.999510646
1403636915751666432 5.292404652 -2.802188158 6.775700569 -0.017806800 -0.007772602 -0.023016160 0.999546289
1403636915801666560 5.304471016 -2.810416460 6.792855263 -0.016591599 -0.007884558 -0.021662952 0.999596536
1403636915851666432 5.326433182 -2.826926231 6.808485508 -0.015893087 -0.008695978 -0.021716638 0.999599993
1403636915901666560 5.344889641 -2.842440367 6.825190067 -0.015224017 -0.008935969 -0.022144713 0.999598920
1403636915951666432 5.364937305 -2.856277943 6.837041855 -0.014777837 -0.008169274 -0.024275107 0.999562740
1403636916001666560 5.381974697 -2.871510506 6.858837128 -0.013687731 -0.006376570 -0.029485278 0.999451160
1403636916051666432 5.401360035 -2.885129452 6.872638226 -0.014133284 -0.005047125 -0.034292955 0.999299169
1403636916101666560 5.424751759 -2.899345875 6.887441635 -0.014235020 -0.004090341 -0.040261652 0.999079406
1403636916151666432 5.445195675 -2.909566164 6.901276112 -0.014519088 -0.003440284 -0.043738075 0.998931587
1403636916201666560 5.465006351 -2.920048714 6.917551994 -0.015158430 -0.003325395 -0.045713790 0.998834014
1403636916251666432 5.483405113 -2.928884029 6.933994293 -0.014877139 -0.003360477 -0.044646565 0.998886406
1403636916301666560 5.503578663 -2.942395449 6.948614120 -0.015474927 -0.004197698 -0.044083428 0.998899162
1403636916351666432 5.518271446 -2.954684019 6.962060928 -0.015547120 -0.004285667 -0.043303017 0.998931825
1403636916401666560 5.536386013 -2.968721867 6.978083611 -0.016626580 -0.003265044 -0.044473737 0.998866856
1403636916451666432 5.552277088 -2.982494116 6.991182327 -0.015701352 0.000497859 -0.047177188 0.998762965
1403636916501666560 5.564853191 -2.994723797 7.012593269 -0.015724868 0.005782226 -0.044983249 0.998847187
1403636916551666432 5.592710972 -3.004528522 7.018985748 -0.014992810 0.011714738 -0.045546636 0.998781025
1403636916601666560 5.610605717 -3.014484167 7.034083843 -0.015112272 0.018830094 -0.043869086 0.998745501
1403636916651666432 5.624255180 -3.020581245 7.047653198 -0.014858681 0.026686087 -0.042689357 0.998621404
1403636916701666560 5.637087822 -3.026845455 7.066734314 -0.014325503 0.033300187 -0.040202651 0.998533726
1403636916751666432 5.657946587 -3.033821344 7.076798916 -0.013928505 0.037624732 -0.038766902 0.998442531
1403636916801666560 5.679221153 -3.038033724 7.085901737 -0.013842836 0.041116726 -0.035896517 0.998413384
1403636916851666432 5.689373016 -3.041934490 7.103117943 -0.013818834 0.045376189 -0.034935277 0.998263240
1403636916901666560 5.706588745 -3.042500496 7.114536285 -0.013666535 0.048751108 -0.034795642 0.998111129
1403636916951666432 5.716845036 -3.042566299 7.133502007 -0.012902496 0.051832661 -0.034555111 0.997974336
1403636917001666560 5.732075691 -3.040892363 7.141448021 -0.012744749 0.052990843 -0.033949748 0.997936368
1403636917051666432 5.739100933 -3.040687084 7.162405491 -0.013226819 0.055369187 -0.032085106 0.997862637
1403636917101666560 5.750893116 -3.034163713 7.176582813 -0.012570099 0.055835564 -0.029824084 0.997915268
1403636917151666432 5.759740353 -3.034476280 7.192293167 -0.013577183 0.056528859 -0.027381942 0.997933090
1403636917201666560 5.769544601 -3.026531458 7.207264423 -0.012755120 0.058190200 -0.024362504 0.997926712
1403636917251666432 5.784100056 -3.019321203 7.229271412 -0.012739833 0.061885085 -0.022030238 0.997758746
1403636917301666560 5.795618057 -3.011074066 7.243114471 -0.011452444 0.067981288 -0.020088110 0.997418582
1403636917351666432 5.805685043 -3.000525475 7.258954525 -0.010934871 0.076280348 -0.018063216 0.996862829
1403636917401666560 5.817978382 -2.991954803 7.272359848 -0.010578413 0.086384475 -0.017082812 0.996059239
1403636917451666432 5.828271389 -2.976723433 7.289220810 -0.008813080 0.096597061 -0.012747998 0.995202899
1403636917501666560 5.836849689 -2.966245890 7.303742886 -0.009759813 0.106355064 -0.010537641 0.994224489
1403636917551666432 5.850572109 -2.955445528 7.318722725 -0.009217906 0.113950886 -0.007430637 0.993415833
1403636917601666560 5.861097336 -2.947549343 7.334602356 -0.008913984 0.120234460 -0.003701210 0.992698610
1403636917651666432 5.872365475 -2.938048363 7.341870308 -0.007601303 0.125729397 -0.001627800 0.992034078
1403636917701666560 5.874258041 -2.927590847 7.358780861 -0.006656674 0.131314516 0.001138342 0.991317749
1403636917751666432 5.879276276 -2.923479080 7.373087883 -0.006005732 0.136897668 0.003123618 0.990562081
1403636917801666560 5.885892868 -2.920348167 7.381347179 -0.005812966 0.141662836 0.003618262 0.989891291
1403636917851666432 5.891001701 -2.920389652 7.391494751 -0.005528898 0.146134779 0.003847602 0.989241779
1403636917901666560 5.901405811 -2.917545319 7.397282124 -0.004609842 0.148915321 0.004621571 0.988828421
1403636917951666432 5.908344269 -2.917624950 7.403434753 -0.004714692 0.151484013 0.004405474 0.988438666
1403636918001666560 5.910493851 -2.918866634 7.407646656 -0.005992091 0.153891250 0.004740063 0.988058269
1403636918051666432 5.911817551 -2.917721272 7.417419910 -0.006965339 0.155911237 0.005184480 0.987732887
1403636918101666560 5.920024395 -2.913359642 7.420466900 -0.007695193 0.157023162 0.003989215 0.987556875
1403636918151666432 5.922750473 -2.910205841 7.427550316 -0.008957532 0.158217937 0.003099304 0.987358689
1403636918201666560 5.919387817 -2.905955315 7.434201241 -0.010420854 0.159672663 0.001781546 0.987113416
1403636918251666432 5.919788837 -2.906122923 7.446980953 -0.011609386 0.160377711 0.000543601 0.986987293
1403636918301666560 5.922827721 -2.903768778 7.451191902 -0.012347703 0.160311475 -0.000557700 0.986989081
1403636918351666432 5.923407555 -2.903290749 7.453454494 -0.015973231 0.160227343 -0.001588148 0.986949623
1403636918401666560 5.923423767 -2.902576685 7.452820778 -0.022508379 0.159267977 -0.000614003 0.986978590
1403636918451666432 5.917085648 -2.908599138 7.464627743 -0.028937407 0.159550235 -0.000183339 0.986765563
1403636918501666560 5.913801193 -2.915998459 7.470036507 -0.033361591 0.158937007 -0.000288323 0.986724854
1403636918551666432 5.911099434 -2.924142361 7.473141670 -0.035475381 0.157899126 0.000246122 0.986817777
1403636918601666560 5.905418396 -2.935852528 7.482659340 -0.036639288 0.157598734 -0.001080595 0.986822665
1403636918651666432 5.900716305 -2.947583914 7.487835884 -0.035526909 0.156085491 -0.001143110 0.987103760
1403636918701666560 5.895500660 -2.967558861 7.497929096 -0.034025904 0.154761493 -0.000155311 0.987365723
1403636918751666432 5.887183666 -2.983823299 7.501206398 -0.030712258 0.152025059 0.003986318 0.987891316
1403636918801666560 5.879569054 -3.006842136 7.512344360 -0.027106864 0.148527041 0.011642998 0.988468170
1403636918851666432 5.871354103 -3.028906345 7.523566723 -0.020929877 0.145274654 0.020446785 0.988958657
1403636918901666560 5.866318703 -3.049188852 7.530651093 -0.014850181 0.144033447 0.025651794 0.989128828
1403636918951666432 5.860805511 -3.075463772 7.544467926 -0.009392952 0.144874200 0.032364968 0.988875985
1403636919001666560 5.859057903 -3.097284555 7.551212788 -0.005985997 0.146748692 0.037354395 0.988450110
1403636919051666432 5.856319904 -3.122034788 7.558292389 -0.002873522 0.148544103 0.041866887 0.988014936
1403636919101666560 5.856648445 -3.144106150 7.562678814 -0.000989720 0.150769845 0.043933365 0.987591684
1403636919151666432 5.859022141 -3.166342258 7.561767578 0.000541363 0.152961642 0.045539491 0.987182140
1403636919201666560 5.860140324 -3.190468550 7.568235397 0.001799733 0.155864060 0.046380103 0.986687362
1403636919251666432 5.864886284 -3.213666916 7.570549011 0.001709888 0.158203200 0.046532869 0.986308038
1403636919301666560 5.873067856 -3.236163616 7.568966866 0.002368131 0.160548031 0.046150140 0.985945702
1403636919351666432 5.880448341 -3.257933617 7.570111275 0.003002808 0.163807616 0.045749649 0.985426307
1403636919401666560 5.881871223 -3.274155617 7.572296143 0.003144926 0.168020353 0.043836392 0.984803379
1403636919451666432 5.889766693 -3.291385412 7.574683189 0.002821831 0.172213331 0.040662430 0.984216034
1403636919501666560 5.903896809 -3.305571079 7.567660809 0.002458886 0.175616294 0.035019558 0.983832538
1403636919551666432 5.914429665 -3.320496082 7.569006443 0.001632536 0.179701775 0.029212309 0.983285964
1403636919601666560 5.930954933 -3.333960295 7.567260265 0.000738065 0.182194367 0.024584552 0.982954860
1403636919651666432 5.937108040 -3.341736317 7.568608761 0.002307803 0.185088187 0.021836324 0.982476592
1403636919701666560 5.946035385 -3.353347778 7.568532467 0.001775972 0.186839685 0.019146636 0.982202232
1403636919751666432 5.957465172 -3.360209465 7.562374592 0.001901828 0.187092125 0.019179825 0.982153237
1403636919801666560 5.965635777 -3.364126444 7.562722206 0.003477950 0.187630251 0.020099517 0.982027888
1403636919851666432 5.978078365 -3.369107008 7.561055183 0.003764553 0.187176421 0.021287309 0.982088387
1403636919901666560 5.984695435 -3.368124247 7.559127331 0.004804578 0.187009603 0.022896191 0.982079506
1403636919951666432 5.996408463 -3.371304035 7.552167892 0.005992201 0.186154932 0.024713153 0.982191265
1403636920001666560 6.006642342 -3.369353294 7.547179699 0.007600845 0.184810832 0.027259765 0.982366621
1403636920051666432 6.015378475 -3.366143465 7.546548367 0.009367285 0.183473632 0.029892785 0.982525349
1403636920101666560 6.023918152 -3.363893032 7.545209885 0.010397963 0.182261795 0.032728005 0.982650161
1403636920151666432 6.033498764 -3.353575230 7.534622669 0.011870398 0.180586159 0.035755709 0.982837319
1403636920201666560 6.044221878 -3.350000858 7.534645081 0.012305499 0.179276779 0.037699640 0.982999027
1403636920251666432 6.052596092 -3.340590000 7.526445389 0.011978004 0.179555863 0.036561199 0.982995152
1403636920301666560 6.062846184 -3.331639051 7.519359589 0.010859988 0.180818155 0.030465886 0.982984602
1403636920351666432 6.072306633 -3.316590548 7.509125233 0.010489023 0.182616100 0.024829732 0.982814789
1403636920401666560 6.088491440 -3.305725098 7.498656273 0.008982152 0.183258250 0.020163560 0.982816935
1403636920451666432 6.093389511 -3.294744015 7.495814800 0.006298957 0.185347304 0.016111255 0.982520759
1403636920501666560 6.107819557 -3.283887863 7.477029800 0.004108788 0.185238272 0.014231390 0.982581973
1403636920551666432 6.116199493 -3.276969671 7.465761185 0.000797180 0.185771227 0.013158057 0.982504606
1403636920601666560 6.116013527 -3.269577026 7.462293625 -0.002408547 0.186510891 0.013152491 0.982361853
1403636920651666432 6.130328178 -3.264562607 7.441879749 -0.006236115 0.186056659 0.013984591 0.982419670
1403636920701666560 6.138488770 -3.258784294 7.418480396 -0.009974662 0.185831830 0.013999415 0.982431233
1403636920751666432 6.144555092 -3.257414579 7.403919220 -0.013183585 0.185943678 0.014849606 0.982359767
1403636920801666560 6.147742748 -3.261826038 7.389611721 -0.016895875 0.186357081 0.015823921 0.982209325
1403636920851666432 6.154206276 -3.262943268 7.373954773 -0.019023271 0.186111599 0.016531998 0.982205331
1403636920901666560 6.153877258 -3.271927357 7.363512993 -0.020603687 0.186654612 0.017557984 0.982052565
1403636920951666432 6.161564827 -3.275176048 7.341341972 -0.021019723 0.186974838 0.017656406 0.981981039
1403636921001666560 6.165249825 -3.276793003 7.322936058 -0.020869307 0.187004939 0.017880438 0.981974483
1403636921051666432 6.170978069 -3.283374548 7.309664249 -0.021258198 0.187189519 0.017756777 0.981933236
1403636921101666560 6.174738884 -3.283755541 7.294016361 -0.020038515 0.187426269 0.018216997 0.981905282
1403636921151666432 6.173233509 -3.284842730 7.284360886 -0.019774776 0.188206792 0.017497741 0.981774390
1403636921201666560 6.170736313 -3.283695698 7.272352695 -0.017353488 0.188754693 0.017345622 0.981717706
1403636921251666432 6.180253029 -3.287484646 7.260270596 -0.012721730 0.188584864 0.016368072 0.981838048
1403636921301666560 6.184623718 -3.285159111 7.245636940 -0.007208835 0.188935563 0.015773309 0.981836319
1403636921351666432 6.181317806 -3.277657509 7.241420746 -0.002150797 0.189046323 0.017658802 0.981806993
1403636921401666560 6.175685883 -3.274511337 7.240143776 0.001141387 0.189139560 0.020603606 0.981733382
1403636921451666432 6.181700706 -3.270690680 7.222546101 0.003778428 0.187662378 0.022989927 0.981957257
1403636921501666560 6.181979179 -3.261953115 7.210656166 0.004249081 0.186250746 0.028319357 0.982084811
1403636921551666432 6.192013741 -3.254746437 7.196972370 0.002906925 0.184506029 0.031714424 0.982315242
1403636921601666560 6.193247318 -3.249064922 7.193002701 -0.000792996 0.183819517 0.035791826 0.982307851
1403636921651666432 6.192718506 -3.238882542 7.183332920 -0.006894034 0.183765575 0.038911320 0.982175410
1403636921701666560 6.195753098 -3.218848944 7.167765141 -0.016282085 0.184207290 0.040208980 0.981929600
1403636921751666432 6.201840401 -3.203738213 7.159189701 -0.025365975 0.184166759 0.041460671 0.981692493
1403636921801666560 6.209595680 -3.189262390 7.146061897 -0.032481693 0.185094297 0.038984854 0.981409788
1403636921851666432 6.219071865 -3.174328327 7.131047249 -0.034505747 0.185693130 0.037154783 0.981298566
1403636921901666560 6.222412109 -3.167236567 7.126832962 -0.034445331 0.187702656 0.034848701 0.981002927
1403636921951666432 6.229828835 -3.151835918 7.120063305 -0.029407803 0.189470112 0.032435987 0.980909824
1403636922001666560 6.236423492 -3.142995358 7.111045837 -0.024633026 0.192053571 0.029369589 0.980635524
1403636922051666432 6.253909588 -3.120815039 7.091264725 -0.017864242 0.194708124 0.026186800 0.980348825
1403636922101666560 6.255307198 -3.115412951 7.100035191 -0.013940307 0.197938174 0.025592493 0.979781151
1403636922151666432 6.266023159 -3.106011868 7.093377113 -0.010738309 0.200786233 0.023923833 0.979284048
1403636922201666560 6.266803741 -3.095331907 7.086189747 -0.009940956 0.204367653 0.023739055 0.978555799
1403636922251666432 6.274055481 -3.087784529 7.079874516 -0.013926095 0.207105547 0.023944715 0.977926373
1403636922301666560 6.302309513 -3.092633963 7.077201366 -0.017245453 0.207928300 0.022926489 0.977723300
1403636922351666432 6.304135799 -3.089233160 7.073170662 -0.020652024 0.210210547 0.024365162 0.977134228
1403636922401666560 6.310992718 -3.078698874 7.063619137 -0.023527360 0.211992174 0.024854975 0.976671875
1403636922451666432 6.319236755 -3.078609943 7.062253952 -0.027880481 0.214378417 0.026082702 0.976004243
1403636922501666560 6.320891380 -3.069785595 7.057567120 -0.030229246 0.218774229 0.028032629 0.974904180
1403636922551666432 6.329392910 -3.065149307 7.049551964 -0.033200320 0.223238066 0.030095534 0.973733425
1403636922601666560 6.337325573 -3.055809975 7.043039322 -0.033056695 0.228335291 0.031641852 0.972506583
1403636922651666432 6.346077919 -3.043363333 7.035164356 -0.029396487 0.233038470 0.034240052 0.971419871
1403636922701666560 6.339357376 -3.036217213 7.043582916 -0.024240499 0.239219487 0.032677967 0.970112681
1403636922751666432 6.352262020 -3.029629469 7.037557602 -0.015677234 0.242582619 0.032827519 0.969448447
1403636922801666560 6.349674225 -3.030480862 7.047992706 -0.008768334 0.245923281 0.035838205 0.968586862
1403636922851666432 6.358451843 -3.025679588 7.039446831 -0.003043973 0.246451005 0.040208083 0.968316019
1403636922901666560 6.336914539 -3.008996725 7.027421474 0.002590090 0.249817252 0.045258347 0.967231274
1403636922951666432 6.346799374 -3.004158974 7.031365871 0.007122413 0.249678433 0.050106909 0.967005312
1403636923001666560 6.346477509 -3.009716034 7.032040596 0.009875705 0.250163853 0.054321028 0.966628015
1403636923051666432 6.349761486 -3.004871130 7.020571232 0.010150675 0.251295924 0.057320066 0.966158211
1403636923101666560 6.356272697 -3.005851269 7.030175209 0.010363686 0.253894955 0.057504077 0.965465248
1403636923151666432 6.351688385 -2.994979620 7.026355743 0.009863444 0.258914590 0.060002711 0.963984251
1403636923201666560 6.355931759 -2.990638256 7.018910408 0.007043329 0.264466405 0.059953485 0.962503791
1403636923251666432 6.357288361 -2.981536150 7.017566681 0.002385488 0.271125585 0.061095066 0.960600138
1403636923301666560 6.354178429 -2.971063614 7.020285606 -0.003140657 0.278114259 0.059972622 0.958668828
1403636923351666432 6.372013092 -2.967107058 6.990827560 -0.010135207 0.282405615 0.059152674 0.957415938
1403636923401666560 6.371045589 -2.945535183 6.988023281 -0.015164653 0.287083447 0.059984058 0.955905378
1403636923451666432 6.374660015 -2.937088013 6.988175869 -0.021685096 0.291413099 0.060953207 0.954407096
1403636923501666560 6.377896309 -2.919246197 6.982814312 -0.027809724 0.293981373 0.062411349 0.953365803
1403636923551666432 6.384442806 -2.914599419 6.983786106 -0.035041876 0.296265811 0.064673662 0.952268839
1403636923601666560 6.391792297 -2.886028767 6.971006870 -0.038977716 0.297272652 0.065713726 0.951730788
1403636923651666432 6.396607399 -2.879941940 6.958143234 -0.041927356 0.298855513 0.067780070 0.950964451
1403636923701666560 6.395809174 -2.874834776 6.958126545 -0.045244720 0.300799757 0.067472532 0.950221002
1403636923751666432 6.404199600 -2.872892857 6.961324215 -0.044611271 0.301487595 0.067853533 0.950005770
1403636923801666560 6.419905663 -2.879286289 6.958568573 -0.044853192 0.301799834 0.066752672 0.949973226
1403636923851666432 6.434110165 -2.879980803 6.947999001 -0.044537757 0.302211642 0.064837992 0.949989796
1403636923901666560 6.436447620 -2.879965305 6.958120346 -0.044901475 0.302321613 0.067088008 0.949781418
1403636923951666432 6.435602665 -2.886980534 6.976320267 -0.045833815 0.303863108 0.065384597 0.949363649
1403636924001666560 6.451545238 -2.891465187 6.957489014 -0.046089068 0.302287459 0.064241104 0.949932158
1403636924051666432 6.454843998 -2.906196594 6.971660137 -0.046999291 0.303330362 0.063984439 0.949572444
1403636924101666560 6.480940819 -2.885941982 6.968955994 -0.044969697 0.301552624 0.062688634 0.950323045
1403636924151666432 6.489020348 -2.881360531 6.986073017 -0.043365654 0.301650673 0.061818056 0.950423479
1403636924201666560 6.501741409 -2.883945942 6.996859550 -0.042878814 0.301564068 0.061017528 0.950524807
1403636924251666432 6.516511917 -2.887669325 7.005105019 -0.043423794 0.300294042 0.058457624 0.951062858
1403636924301666560 6.526860237 -2.885066986 7.032310486 -0.040412381 0.300061464 0.059427511 0.951208830
1403636924351666432 6.542019844 -2.885008335 7.048394203 -0.039238822 0.298496783 0.061706688 0.951605082
1403636924401666560 6.549537659 -2.901092529 7.061656952 -0.036246274 0.296664923 0.065503076 0.952042818
1403636924451666432 6.565711975 -2.908842087 7.084355354 -0.031165021 0.295071840 0.069422342 0.952439964
1403636924501666560 6.578441620 -2.900610447 7.095865726 -0.023684410 0.293285817 0.071585007 0.953046679
1403636924551666432 6.586071014 -2.928862572 7.126649380 -0.019350749 0.293337107 0.074921697 0.952872276
1403636924601666560 6.601802349 -2.945991755 7.136106491 -0.013835604 0.290743768 0.078712173 0.953457415
1403636924651666432 6.613294601 -2.949386358 7.147348404 -0.008344208 0.288887411 0.082299910 0.953782558
1403636924701666560 6.641252518 -2.964598894 7.161886692 -0.004791425 0.287031233 0.083451681 0.954267204
1403636924751666432 6.654491425 -2.968372107 7.189895153 0.000448666 0.285573184 0.084884398 0.954590201
1403636924801666560 6.662763596 -2.978318691 7.210803509 0.004990845 0.284395039 0.086970098 0.954741180
1403636924851666432 6.684096336 -2.983651876 7.221139908 0.009155969 0.283089042 0.087540574 0.955046296
1403636924901666560 6.703480721 -2.986632109 7.232666016 0.011841575 0.283170223 0.086840458 0.955056608
1403636924951666432 6.732370377 -2.986728430 7.242454052 0.013030805 0.285654128 0.088492058 0.954149365
1403636925001666560 6.741009235 -2.994050980 7.253769875 0.011841171 0.290736139 0.089546680 0.952530146
1403636925051666432 6.776561737 -2.980007410 7.272358894 0.009524384 0.295501322 0.086928830 0.951331496
1403636925101666560 6.788296223 -2.963333607 7.281722546 0.008418739 0.301666468 0.084023759 0.949666500
1403636925151666432 6.815184593 -2.956788301 7.295567036 0.002682414 0.307129890 0.077911437 0.948469162
1403636925201666560 6.837867260 -2.972519398 7.299050331 -0.003789442 0.312296450 0.073273383 0.947147071
1403636925251666432 6.857037067 -2.961513996 7.315397739 -0.010392606 0.316873670 0.069312267 0.945874631
1403636925301666560 6.886985779 -2.956149817 7.316773415 -0.018755216 0.319468528 0.067396857 0.945010960
1403636925351666432 6.907822609 -2.943525791 7.321746349 -0.026440609 0.321901470 0.066763014 0.944046080
1403636925401666560 6.926898479 -2.928603649 7.334843636 -0.034572247 0.324190170 0.067337088 0.942958772
1403636925451666432 6.955041409 -2.911740780 7.356720924 -0.040038507 0.325624168 0.068755150 0.942145705
1403636925501666560 6.974800587 -2.912465811 7.359086037 -0.046013787 0.326574504 0.070319578 0.941428185
1403636925551666432 6.994811058 -2.879470348 7.388510227 -0.049591914 0.328406245 0.070896342 0.940565646
1403636925601666560 7.013499260 -2.874621868 7.396551132 -0.054381054 0.328636855 0.072323717 0.940111578
1403636925651666432 7.033461094 -2.879031658 7.421101093 -0.058246974 0.329467803 0.075807266 0.939314365
1403636925701666560 7.069187164 -2.881992817 7.424631119 -0.061270341 0.328987926 0.074857973 0.939366341
1403636925751666432 7.103641510 -2.861726999 7.442314148 -0.061040942 0.329447687 0.074507594 0.939248025
1403636925801666560 7.124786377 -2.883172035 7.475391865 -0.062580846 0.330945104 0.073382415 0.938708663
1403636925851666432 7.153299809 -2.890241146 7.492100239 -0.058741633 0.331243724 0.072296284 0.938935697
1403636925901666560 7.180934906 -2.899650097 7.513534069 -0.050911497 0.331563503 0.070512928 0.939415574
1403636925951666432 7.201198101 -2.933668613 7.543439865 -0.044124894 0.333356827 0.066612303 0.939408839
1403636926001666560 7.251846313 -2.923676252 7.560672283 -0.032197785 0.332732052 0.063689254 0.940317154
1403636926051666432 7.261703491 -2.942218781 7.605341434 -0.021001266 0.333947152 0.062179904 0.940304160
1403636926101666560 7.287736893 -2.951638699 7.623348236 -0.011272850 0.333200246 0.062568352 0.940710187
1403636926151666432 7.320073128 -2.967169523 7.636904240 -0.003345215 0.330731153 0.064609416 0.941504836
1403636926201666560 7.361040115 -2.980409145 7.660654545 0.003041923 0.327720255 0.067932636 0.942324460
1403636926251666432 7.385010719 -2.974623442 7.700131416 0.008829885 0.326836795 0.070171453 0.942430735
1403636926301666560 7.421293736 -2.972001553 7.748908043 0.012256838 0.325685948 0.072380140 0.942623794
1403636926351666432 7.439092159 -2.976670265 7.760659218 0.015721492 0.323107362 0.076233864 0.943155825
1403636926401666560 7.459120750 -2.961620331 7.792057037 0.019177880 0.321380347 0.078881107 0.943464220
1403636926451666432 7.477513313 -2.965291500 7.808323860 0.019943152 0.319783807 0.080517009 0.943852544
1403636926501666560 7.497793674 -2.951271772 7.813380718 0.019428553 0.317674816 0.081295677 0.944508493
1403636926551666432 7.521666527 -2.966787577 7.843116760 0.015361699 0.317948073 0.079794809 0.944619417
1403636926601666560 7.548880577 -2.961941719 7.875313759 0.012808099 0.318644136 0.078029275 0.944570422
1403636926651666432 7.567308426 -2.966145754 7.887869358 0.009768930 0.319143951 0.074891649 0.944692016
1403636926701666560 7.587147236 -2.965383053 7.915386677 0.006773918 0.319747746 0.074207798 0.944568038
1403636926751666432 7.598059177 -2.955470562 7.912702560 0.003528567 0.320083708 0.074523948 0.944446981
1403636926801666560 7.620883942 -2.959613323 7.928972244 0.000757624 0.321537375 0.077955246 0.943682194
1403636926851666432 7.648954868 -2.965358734 7.942681313 -0.002457370 0.323912412 0.081622183 0.942556381
1403636926901666560 7.664928913 -2.965524197 7.949631691 -0.002774775 0.327884674 0.086952411 0.940703630
1403636926951666432 7.683858871 -2.972545862 7.953871727 -0.003604103 0.332814187 0.092492796 0.938438535
1403636927001666560 7.699368954 -2.985483885 7.959871769 -0.003212945 0.340156913 0.096744262 0.935373425
1403636927051666432 7.724190235 -2.980655670 7.960905075 -0.002364492 0.347486258 0.099879354 0.932347476
1403636927101666560 7.754889488 -2.987322807 7.981102467 -0.002214576 0.357027382 0.102830492 0.928413928
1403636927151666432 7.777927876 -2.975132704 7.987384796 -0.000913781 0.366322577 0.106220119 0.924404800
1403636927201666560 7.795763969 -2.979221344 7.997756004 -0.000754788 0.377646148 0.109457895 0.919457316
1403636927251666432 7.830347538 -2.992686272 8.012078285 -0.001624321 0.389043242 0.112826958 0.914282680
1403636927301666560 7.858222008 -2.987207413 8.021854401 -0.002642376 0.400161922 0.114394821 0.909272969
1403636927351666432 7.876943588 -2.966632843 8.035448074 -0.003830832 0.410324395 0.115426652 0.904597104
1403636927401666560 7.904747963 -2.970423222 8.033840179 -0.011252864 0.418265879 0.116174757 0.900794387
1403636927451666432 7.941668510 -2.951161861 8.028388023 -0.018273970 0.423647851 0.118256867 0.897888601
1403636927501666560 7.948831558 -2.940870762 8.046657562 -0.025415435 0.430261970 0.120378762 0.894280553
1403636927551666432 8.006660461 -2.929806948 8.047389984 -0.033510733 0.432865262 0.122905821 0.892411828
1403636927601666560 8.021296501 -2.926691055 8.055055618 -0.039127607 0.436882883 0.126469776 0.889723420
1403636927651666432 8.044190407 -2.928730965 8.067307472 -0.043606792 0.440883815 0.126503721 0.887534082
1403636927701666560 8.081149101 -2.915244102 8.067564011 -0.045876678 0.442408204 0.127043262 0.886583507
1403636927751666432 8.107962608 -2.911087036 8.082834244 -0.046469528 0.444711328 0.128538460 0.885183752
1403636927801666560 8.138184547 -2.908077717 8.091332436 -0.045297306 0.445759863 0.129751876 0.884539843
1403636927851666432 8.180442810 -2.913852453 8.098013878 -0.044997074 0.446064949 0.130195841 0.884336174
1403636927901666560 8.216347694 -2.918237448 8.105533600 -0.043540806 0.446290970 0.129961297 0.884329498
1403636927951666432 8.255149841 -2.927629471 8.110445976 -0.042898435 0.446185589 0.129387766 0.884498119
1403636928001666560 8.278793335 -2.936696768 8.132382393 -0.041967154 0.447244644 0.129739389 0.883956254
1403636928051666432 8.306329727 -2.915729046 8.166646004 -0.037649099 0.448814064 0.127509683 0.883679688
1403636928101666560 8.361670494 -2.942602873 8.183560371 -0.035866614 0.448644429 0.125219032 0.884167373
1403636928151666432 8.403385162 -2.942222357 8.199542999 -0.030909058 0.448571295 0.122778855 0.884733737
1403636928201666560 8.443812370 -2.954446793 8.223373413 -0.024195505 0.448973000 0.120816231 0.885009170
1403636928251666432 8.478480339 -2.964452028 8.255096436 -0.016798850 0.449278682 0.120338857 0.885090411
1403636928301666560 8.517455101 -2.950274229 8.274566650 -0.009150691 0.448578775 0.118995555 0.885738909
1403636928351666432 8.556289673 -2.945118904 8.292037010 -0.002013255 0.447991908 0.117299899 0.886306882
1403636928401666560 8.596508026 -2.951616287 8.308996201 0.000693587 0.447624832 0.115627483 0.886714041
1403636928451666432 8.629667282 -2.948317528 8.332827568 0.003736680 0.447758794 0.114402018 0.886797786
1403636928501666560 8.689287186 -2.955226660 8.346847534 0.004015015 0.447224110 0.112385735 0.887324035
1403636928551666432 8.724147797 -2.951566935 8.360446930 0.003223635 0.446819961 0.110880539 0.887720168
1403636928601666560 8.762153625 -2.952633619 8.381178856 0.000480339 0.446756482 0.110750861 0.887773991
1403636928651666432 8.795032501 -2.955509663 8.395405769 -0.004069118 0.446658909 0.110715151 0.887818336
1403636928701666560 8.828859329 -2.950121641 8.411289215 -0.008971157 0.445959121 0.111059800 0.888091087
1403636928751666432 8.868664742 -2.958206654 8.431227684 -0.014595783 0.445763499 0.112345397 0.887952924
1403636928801666560 8.900107384 -2.967326164 8.445867538 -0.018765513 0.445589155 0.112583652 0.887931883
1403636928851666432 8.937150955 -2.970086813 8.457596779 -0.021431908 0.445141464 0.112962835 0.888047934
1403636928901666560 8.970847130 -2.982919216 8.479138374 -0.022012424 0.445854664 0.112863012 0.887688577
1403636928951666432 9.003695488 -3.000579357 8.505476952 -0.019992417 0.447174370 0.110215962 0.887405097
1403636929001666560 9.039481163 -3.018392801 8.519208908 -0.011839786 0.446894437 0.110418439 0.887667120
1403636929051666432 9.066835403 -3.039325714 8.535128593 -0.003385535 0.446581930 0.111387029 0.887775898
1403636929101666560 9.100857735 -3.048189640 8.554915428 0.005395168 0.445923716 0.113286123 0.887856483
1403636929151666432 9.133878708 -3.074634552 8.566248894 0.010584941 0.445020676 0.115709782 0.887950301
1403636929201666560 9.165019989 -3.097645760 8.576009750 0.013334853 0.443580806 0.118507452 0.888264716
1403636929251666432 9.199162483 -3.119104385 8.590511322 0.014144100 0.442558855 0.121231914 0.888394296
1403636929301666560 9.225653648 -3.140511274 8.597523689 0.014806727 0.441205502 0.125117585 0.888517857
1403636929351666432 9.271932602 -3.166955233 8.596623421 0.013905672 0.438778788 0.126915768 0.889478624
1403636929401666560 9.297462463 -3.176134348 8.607575417 0.013558987 0.439118356 0.125638023 0.889497817
1403636929451666432 9.328368187 -3.194413662 8.617250443 0.012288222 0.439035386 0.125361010 0.889596283
1403636929501666560 9.367192268 -3.198094130 8.620237350 0.009440606 0.438955128 0.121624500 0.890189171
1403636929551666432 9.390413284 -3.213743210 8.630620956 0.005919142 0.440576077 0.118316352 0.889864564
1403636929601666560 9.421563148 -3.216261864 8.643660545 0.003962150 0.441818595 0.113858528 0.889840961
1403636929651666432 9.450793266 -3.219625473 8.645176888 0.001015201 0.442794442 0.109233834 0.889943838
1403636929701666560 9.479213715 -3.222188950 8.656488419 0.000340682 0.443630487 0.106183849 0.889897108
1403636929751666432 9.517607689 -3.238380432 8.653476715 -0.002069231 0.443502963 0.103813373 0.890237987
1403636929801666560 9.549471855 -3.244926929 8.654447556 -0.003804450 0.442968607 0.103186816 0.890571058
1403636929851666432 9.569849968 -3.237869740 8.667398453 -0.002246917 0.443697929 0.103006944 0.890234053
1403636929901666560 9.597708702 -3.246795177 8.675132751 -0.001502829 0.443092316 0.104338691 0.890382171
1403636929951666432 9.631347656 -3.254216433 8.675314903 -0.000855738 0.441500098 0.105921522 0.890986860
1403636930001666560 9.657152176 -3.257618427 8.679722786 0.001091175 0.440459728 0.108471766 0.891194642
1403636930051666432 9.680933952 -3.259572983 8.688622475 0.002745736 0.440019697 0.110194013 0.891197205
1403636930101666560 9.698817253 -3.269001484 8.693602562 0.001607093 0.440172017 0.111225836 0.890996516
1403636930151666432 9.717792511 -3.272319794 8.700994492 0.003404423 0.439983666 0.114251897 0.890701532
1403636930201666560 9.749114037 -3.283084393 8.695085526 0.002677490 0.438709676 0.114993788 0.891236842
1403636930251666432 9.768051147 -3.295231342 8.693740845 0.001846364 0.437878698 0.116986133 0.891388297
1403636930301666560 9.786453247 -3.303394556 8.698499680 0.001854330 0.438075900 0.119370081 0.890975237
1403636930351666432 9.802420616 -3.317800999 8.696743011 0.001202573 0.438601434 0.118626349 0.890817106
1403636930401666560 9.828546524 -3.324275017 8.694530487 0.001828105 0.439570248 0.115552478 0.890742540
1403636930451666432 9.852474213 -3.337590456 8.690992355 -0.000522884 0.440936804 0.111845195 0.890542030
1403636930501666560 9.872329712 -3.344455004 8.688220978 -0.000222878 0.441823244 0.109396793 0.890406907
1403636930551666432 9.895584106 -3.355432034 8.687398911 -0.000070089 0.442697763 0.107291847 0.890228748
1403636930601666560 9.914894104 -3.365724087 8.683278084 -0.000721412 0.442676872 0.107181981 0.890252054
1403636930651666432 9.938493729 -3.371675968 8.678344727 0.000842797 0.441807091 0.108090803 0.890574098
1403636930701666560 9.952643394 -3.381770611 8.684694290 0.002056148 0.441356927 0.111916751 0.890322685
1403636930751666432 9.971736908 -3.375738859 8.676472664 0.004593127 0.439553022 0.114705637 0.890850544
1403636930801666560 9.991650581 -3.376492500 8.676144600 0.007151098 0.437830687 0.119792320 0.891012311
1403636930851666432 10.010133743 -3.379389524 8.676107407 0.008284112 0.437544823 0.121773675 0.890874326
1403636930901666560 10.024615288 -3.368745327 8.678305626 0.011523481 0.437782139 0.125276685 0.890235841
1403636930951666432 10.050694466 -3.372957945 8.673088074 0.012961342 0.438225269 0.130942538 0.889182031
1403636931001666560 10.068391800 -3.371912718 8.664033890 0.015236485 0.440396011 0.136598065 0.887220502
1403636931051666432 10.089920044 -3.366871357 8.665969849 0.016178014 0.445143819 0.139519051 0.884375334
1403636931101666560 10.110961914 -3.353774071 8.645390511 0.017734544 0.449636340 0.137818739 0.882337034
1403636931151666432 10.131027222 -3.349036694 8.637034416 0.019056465 0.456041396 0.132976919 0.879761457
1403636931201666560 10.154379845 -3.345755100 8.627124786 0.018299131 0.462034136 0.127679870 0.877432287
1403636931251666432 10.176032066 -3.343234539 8.611019135 0.020066973 0.467347383 0.122483030 0.875318050
1403636931301666560 10.190909386 -3.337305307 8.600584030 0.022484487 0.472025067 0.118096158 0.873349905
1403636931351666432 10.204943657 -3.333473682 8.582036018 0.022142852 0.475960523 0.114234746 0.871734917
1403636931401666560 10.236433983 -3.335455418 8.562905312 0.020985689 0.478383392 0.110847712 0.870874107
1403636931451666432 10.248336792 -3.341286182 8.547702789 0.016982043 0.482097983 0.106707297 0.869428933
1403636931501666560 10.255474091 -3.338765621 8.535023689 0.014292119 0.486037493 0.102157094 0.867829025
1403636931551666432 10.271749496 -3.348480701 8.500931740 0.009575239 0.487990081 0.097614065 0.867320895
1403636931601666560 10.272063255 -3.339156866 8.493701935 0.007443596 0.491624177 0.093235381 0.865769863
1403636931651666432 10.295422554 -3.350427151 8.464344978 0.004220895 0.492553562 0.088566124 0.865753531
1403636931701666560 10.295766830 -3.346621275 8.448451042 0.004625665 0.493887901 0.088418350 0.865006089
1403636931751666432 10.297036171 -3.349702358 8.425483704 0.004126493 0.492155820 0.094293892 0.865375221
1403636931801666560 10.297340393 -3.346598387 8.419151306 0.004189558 0.491069049 0.101500317 0.865177035
1403636931851666432 10.305981636 -3.354025126 8.390456200 0.002121692 0.488056690 0.108398095 0.866051972
1403636931901666560 10.303961754 -3.341035366 8.380691528 0.001625193 0.487222016 0.112802528 0.865960538
1403636931951666432 10.287063599 -3.332854748 8.379591942 0.000775906 0.487623394 0.116911650 0.865190446
1403636932001666560 10.300887108 -3.333667755 8.350626945 0.000530543 0.485538244 0.119273439 0.866040528
1403636932051666432 10.299662590 -3.326071739 8.338487625 0.002504014 0.486162573 0.118897840 0.865738392
1403636932101666560 10.302539825 -3.320441723 8.318215370 0.004559510 0.485413045 0.119777098 0.866029322
1403636932151666432 10.296502113 -3.309351683 8.313285828 0.007079665 0.486317843 0.119729690 0.865511179
1403636932201666560 10.292278290 -3.294404507 8.300422668 0.009088265 0.487649024 0.116945028 0.865124106
1403636932251666432 10.289665222 -3.289812326 8.283462524 0.009716532 0.489906430 0.112095088 0.864483595
1403636932301666560 10.279308319 -3.281327248 8.275487900 0.009767668 0.493324339 0.106412441 0.863256693
1403636932351666432 10.276750565 -3.269725323 8.254179001 0.008743661 0.495318443 0.101031795 0.862772107
1403636932401666560 10.267608643 -3.265410662 8.236017227 0.007851888 0.497669697 0.096778899 0.861914754
1403636932451666432 10.256505966 -3.261803865 8.223050117 0.007982902 0.500276625 0.095039442 0.860596955
1403636932501666560 10.246650696 -3.257614136 8.205715179 0.007862620 0.502756119 0.095605664 0.859089077
1403636932551666432 10.229863167 -3.254089832 8.189771652 0.007564702 0.506332219 0.098661944 0.856642425
1403636932601666560 10.215528488 -3.259303808 8.170220375 0.007356355 0.511014640 0.103159927 0.853327572
1403636932651666432 10.197978020 -3.262099743 8.154622078 0.008184066 0.516095340 0.109601170 0.849450588
1403636932701666560 10.180065155 -3.270940781 8.135346413 0.010301724 0.521042407 0.115476012 0.845620513
1403636932751666432 10.159707069 -3.274017811 8.116018295 0.011488737 0.526090980 0.118567117 0.842043996
1403636932801666560 10.138006210 -3.286365032 8.095374107 0.012539582 0.530315757 0.122088097 0.838869750
1403636932851666432 10.108856201 -3.291165113 8.086203575 0.012898893 0.535884321 0.124999173 0.834887266
1403636932901666560 10.084751129 -3.298235893 8.064856529 0.011527432 0.539355040 0.128038988 0.832207441
1403636932951666432 10.067124367 -3.310906887 8.044168472 0.009112071 0.542216718 0.130529717 0.829987943
1403636933001666560 10.041454315 -3.311975002 8.025649071 0.007612431 0.545295119 0.133277267 0.827546000
1403636933051666432 10.013878822 -3.309856653 8.011058807 0.006487143 0.550268412 0.135335371 0.823921680
1403636933101666560 9.978656769 -3.305894375 8.006643295 0.006130023 0.555332422 0.138333365 0.820019603
1403636933151666432 9.957358360 -3.296312332 7.986973763 0.004794900 0.558270812 0.140543550 0.817654073
1403636933201666560 9.926611900 -3.285602093 7.966721535 -0.000364818 0.559453845 0.146756425 0.815765798
1403636933251666432 9.899217606 -3.273296118 7.956270218 -0.009020383 0.560617447 0.152952388 0.813776553
1403636933301666560 9.874708176 -3.271333694 7.942834377 -0.019111771 0.560794175 0.160028443 0.812117934
1403636933351666432 9.848457336 -3.252712011 7.935627937 -0.024393968 0.560567260 0.165149540 0.811107159
1403636933401666560 9.831768990 -3.244524479 7.921708584 -0.027589204 0.559673965 0.169096246 0.810808480
1403636933451666432 9.794721603 -3.231349945 7.921679497 -0.025488446 0.561632693 0.169321388 0.809474707
1403636933501666560 9.772047997 -3.217868090 7.912565231 -0.022783980 0.562212527 0.167857558 0.809457719
1403636933551666432 9.751001358 -3.214101315 7.908401966 -0.019782737 0.563522160 0.165405393 0.809130728
1403636933601666560 9.731400490 -3.196219921 7.897770882 -0.015252389 0.563598335 0.162313461 0.809801579
1403636933651666432 9.710621834 -3.195985556 7.897104263 -0.012401893 0.564574361 0.159937426 0.809643090
1403636933701666560 9.692181587 -3.183523655 7.888000488 -0.008502638 0.564781308 0.156829178 0.810157001
1403636933751666432 9.675500870 -3.178276777 7.876023769 -0.005710165 0.564934194 0.153447092 0.810722291
1403636933801666560 9.660433769 -3.189857244 7.873392105 -0.003314066 0.564965010 0.151551634 0.811070681
1403636933851666432 9.630684853 -3.184931278 7.868538857 0.001124667 0.564768434 0.150729969 0.811366618
1403636933901666560 9.618143082 -3.188804150 7.849787712 0.003591125 0.564098656 0.150655508 0.811839104
1403636933951666432 9.596192360 -3.188835621 7.843923092 0.004930096 0.565682530 0.151798561 0.810516000
1403636934001666560 9.575100899 -3.187545300 7.843306065 0.006698060 0.568665802 0.154565275 0.807888508
1403636934051666432 9.556737900 -3.187248945 7.822559357 0.007696567 0.572206676 0.156937882 0.804916620
1403636934101666560 9.538611412 -3.188874722 7.812801361 0.007437981 0.578274310 0.159562886 0.800051987
1403636934151666432 9.517730713 -3.183800697 7.799939632 0.006854663 0.585931957 0.161424503 0.794089973
1403636934201666560 9.495111465 -3.162702322 7.797344208 0.007899838 0.595008373 0.162764952 0.787026167
1403636934251666432 9.477525711 -3.153329849 7.794673443 0.007522308 0.604469717 0.165567204 0.779196560
1403636934301666560 9.459300041 -3.138364315 7.792328835 0.008751832 0.614227831 0.168791667 0.770815790
1403636934351666432 9.437669754 -3.125256777 7.774410248 0.010657813 0.623220265 0.173685595 0.762440979
1403636934401666560 9.415897369 -3.111211777 7.775072575 0.013768014 0.632802069 0.180425167 0.752873659
1403636934451666432 9.390737534 -3.091384649 7.766679764 0.016455315 0.641450942 0.188283458 0.743518174
1403636934501666560 9.368767738 -3.076335907 7.746464729 0.018847117 0.650386095 0.193155214 0.734393477
1403636934551666432 9.347226143 -3.067615032 7.738584042 0.020215947 0.659705639 0.198910534 0.724440753
1403636934601666560 9.319851875 -3.062387228 7.728770256 0.019920485 0.670032263 0.202328920 0.713948905
1403636934651666432 9.296759605 -3.054245472 7.707966328 0.020836852 0.678587079 0.206025407 0.704726160
1403636934701666560 9.276990891 -3.050084114 7.694369793 0.017510416 0.685798705 0.209862173 0.696657360
1403636934751666432 9.256614685 -3.050409079 7.685858250 0.012739699 0.692852914 0.212372065 0.688978016
1403636934801666560 9.233639717 -3.042540312 7.662249565 0.007458829 0.697631419 0.213547915 0.683850884
1403636934851666432 9.211222649 -3.041396618 7.645884037 0.002002344 0.701936781 0.214779466 0.679080665
1403636934901666560 9.190947533 -3.045492411 7.634003162 -0.002702436 0.705382168 0.216286078 0.675017834
1403636934951666432 9.170721054 -3.052028656 7.599906921 -0.005252114 0.706587970 0.218359470 0.673071325
1403636935001666560 9.141434669 -3.049975157 7.586799145 -0.006694964 0.708559692 0.218083411 0.671072304
1403636935051666432 9.126983643 -3.054372072 7.554618835 -0.007182006 0.709441960 0.215315536 0.671028912
1403636935101666560 9.099667549 -3.076115608 7.546459198 -0.004395422 0.710904002 0.213852361 0.669972658
1403636935151666432 9.081051826 -3.077770710 7.534026623 -0.000272668 0.711786687 0.209886119 0.670304060
1403636935201666560 9.050872803 -3.091040611 7.513503551 0.005645717 0.711036742 0.209667355 0.671144128
1403636935251666432 9.031315804 -3.104571104 7.496348858 0.008210991 0.710437536 0.208972022 0.671968579
1403636935301666560 9.016751289 -3.113398552 7.467674732 0.011172088 0.708520532 0.209882364 0.673664033
1403636935351666432 8.991267204 -3.120707512 7.457089901 0.013358545 0.707762957 0.209597275 0.674508810
1403636935401666560 8.976551056 -3.130360365 7.442147255 0.013972932 0.706308663 0.211214781 0.675515473
1403636935451666432 8.951289177 -3.128894806 7.419859409 0.014724265 0.704952598 0.210783616 0.677048981
1403636935501666560 8.932459831 -3.133800507 7.401923656 0.015008550 0.704006791 0.210670099 0.678061366
1403636935551666432 8.908267021 -3.129473925 7.384726048 0.014784128 0.703004777 0.209722444 0.679398417
1403636935601666560 8.890132904 -3.126452923 7.368290901 0.015428536 0.702201188 0.209861666 0.680171728
1403636935651666432 8.870332718 -3.122634172 7.348519325 0.015613757 0.701083720 0.209780902 0.681344092
1403636935701666560 8.846656799 -3.116035938 7.334509373 0.015320644 0.700873077 0.208753347 0.681882799
1403636935751666432 8.825664520 -3.102679253 7.321562290 0.012772100 0.699864089 0.210594714 0.682405293
1403636935801666560 8.804039955 -3.093517065 7.295963287 0.007785778 0.698245227 0.211962223 0.683714151
1403636935851666432 8.777020454 -3.086165905 7.286408424 0.003266342 0.697820306 0.214348421 0.683440447
1403636935901666560 8.740715027 -3.105196476 7.285332203 -0.003011852 0.697335362 0.218720675 0.682550788
1403636935951666432 8.723427773 -3.090577364 7.268270969 -0.007748863 0.694797695 0.225545913 0.682880044
1403636936001666560 8.703924179 -3.075966358 7.253980160 -0.013393203 0.693044007 0.230559930 0.682900250
1403636936051666432 8.692945480 -3.064143896 7.231705189 -0.017547855 0.691202044 0.234509259 0.683328032
1403636936101666560 8.671978951 -3.044655085 7.219077110 -0.019612864 0.690631330 0.236031696 0.683324754
1403636936151666432 8.665067673 -3.034927607 7.206126690 -0.021510750 0.691209018 0.235337570 0.682922840
1403636936201666560 8.661200523 -2.986888170 7.183305740 -0.019766558 0.691815019 0.231877223 0.683545291
1403636936251666432 8.657550812 -2.965932846 7.167650223 -0.018654257 0.693056226 0.228785291 0.683361113
1403636936301666560 8.657603264 -2.949761152 7.142838478 -0.015189331 0.694411576 0.224746525 0.683411181
1403636936351666432 8.640551567 -2.942512989 7.127425671 -0.011323481 0.696116686 0.221511275 0.682807505
1403636936401666560 8.634664536 -2.932950258 7.106637001 -0.008363034 0.697618961 0.217992917 0.682449222
1403636936451666432 8.633573532 -2.910319805 7.083292007 -0.002237623 0.698528647 0.215286046 0.682425559
1403636936501666560 8.630019188 -2.920270443 7.073890209 -0.001180608 0.701141417 0.211282149 0.680998564
1403636936551666432 8.617396355 -2.931629658 7.050790310 0.000484309 0.702165127 0.210600972 0.680155218
1403636936601666560 8.610395432 -2.923730612 7.032857895 0.002233875 0.703688025 0.209084988 0.679044664
1403636936651666432 8.611316681 -2.918187618 7.010198116 0.003206889 0.704106092 0.209928319 0.678346813
1403636936701666560 8.604440689 -2.911311626 6.992543697 0.003222942 0.704954326 0.209847718 0.677490234
1403636936751666432 8.604040146 -2.899115562 6.974800110 0.002739583 0.705890179 0.208958313 0.676792383
1403636936801666560 8.603610992 -2.887326002 6.953651428 0.002482527 0.706439674 0.208645880 0.676316321
1403636936851666432 8.597440720 -2.875105381 6.934028625 0.000051311 0.707399428 0.207589746 0.675642312
1403636936901666560 8.596419334 -2.861309052 6.908593178 -0.000439050 0.707888663 0.206383884 0.675499141
1403636936951666432 8.596037865 -2.856379271 6.900358677 -0.001744938 0.709025741 0.206131786 0.674380541
1403636937001666560 8.590191841 -2.847715378 6.877848625 -0.003081678 0.709440649 0.204854175 0.674328744
1403636937051666432 8.590720177 -2.843108177 6.857814789 -0.003945987 0.710033119 0.204563245 0.673788786
1403636937101666560 8.590362549 -2.849577427 6.841389179 -0.004415816 0.710203409 0.206032529 0.673158348
1403636937151666432 8.588269234 -2.843718767 6.827867031 -0.002757852 0.710250616 0.207108140 0.672787249
1403636937201666560 8.594772339 -2.827074289 6.803102970 0.000522547 0.709732115 0.208344653 0.672958016
1403636937251666432 8.596054077 -2.825186491 6.782366753 0.001294997 0.709594488 0.209657848 0.672694266
1403636937301666560 8.591279030 -2.820837498 6.767969131 0.001518753 0.710024416 0.209449887 0.672304749
1403636937351666432 8.589277267 -2.821755171 6.749727726 0.002302004 0.710371315 0.209635362 0.671878159
1403636937401666560 8.588851929 -2.811779499 6.726278305 0.001996027 0.710445344 0.209467188 0.671853304
1403636937451666432 8.591052055 -2.806727886 6.721266747 0.002277154 0.711076677 0.209906533 0.671046913
1403636937501666560 8.578348160 -2.800479889 6.703460693 0.002495433 0.711449862 0.209504038 0.670776308
1403636937551666432 8.579389572 -2.794020891 6.690431118 0.002290110 0.712128401 0.208801419 0.670275927
1403636937601666560 8.580402374 -2.790563345 6.670955181 0.001462996 0.712230742 0.209119141 0.670070469
1403636937651666432 8.571897507 -2.801219940 6.658115864 -0.002338647 0.713539839 0.208441898 0.668885171
1403636937701666560 8.563879013 -2.780958891 6.658878326 -0.004794587 0.715458751 0.205099359 0.667854846
1403636937751666432 8.565887451 -2.765185595 6.639166832 -0.008500955 0.716704249 0.200645685 0.667835295
1403636937801666560 8.572668076 -2.734868288 6.628170490 -0.008730703 0.717993736 0.198471114 0.667096734
1403636937851666432 8.573369980 -2.712061167 6.612611771 -0.006970590 0.719093680 0.195119932 0.666921198
1403636937901666560 8.575984955 -2.702279806 6.600207806 -0.005933983 0.721053004 0.189584896 0.666411996
1403636937951666432 8.567895889 -2.685428619 6.605380058 -0.004032512 0.723779202 0.184798792 0.664813280
1403636938001666560 8.579088211 -2.670377731 6.589731693 -0.002206463 0.725098431 0.180881321 0.664461732
1403636938051666432 8.561920166 -2.668309927 6.592052460 -0.000596769 0.727185547 0.177588940 0.663070858
1403636938101666560 8.560031891 -2.626492977 6.586290836 0.004918289 0.729015112 0.174669564 0.661818206
1403636938151666432 8.557811737 -2.617054939 6.585495949 0.009183107 0.730927587 0.175451368 0.659452260
1403636938201666560 8.551399231 -2.595452785 6.583615780 0.014811788 0.731640220 0.178522542 0.657733142
1403636938251666432 8.540013313 -2.575614452 6.590118885 0.019657856 0.732800603 0.181124970 0.655599415
1403636938301666560 8.534746170 -2.561246634 6.589874268 0.025743041 0.732765913 0.186528549 0.653910160
1403636938351666432 8.517795563 -2.547981739 6.585435867 0.033603564 0.730699718 0.196602523 0.652913570
1403636938401666560 8.509099960 -2.537907600 6.588955402 0.040441006 0.728550613 0.207297415 0.651618183
1403636938451666432 8.490134239 -2.531743526 6.590007305 0.045578912 0.725972235 0.218982205 0.650333524
1403636938501666560 8.467315674 -2.528364658 6.590104103 0.047743414 0.724452257 0.227151677 0.649069726
1403636938551666432 8.446090698 -2.512557030 6.582578659 0.046512965 0.723403931 0.233296633 0.648148119
1403636938601666560 8.435061455 -2.511101723 6.572544098 0.044981845 0.722975850 0.237539828 0.647191882
1403636938651666432 8.415019035 -2.505539894 6.558116913 0.044307884 0.722520411 0.241062373 0.646444142
1403636938701666560 8.390407562 -2.496631145 6.547258854 0.042802390 0.723430037 0.240580231 0.645707488
1403636938751666432 8.371593475 -2.488127708 6.529952526 0.040033676 0.724451542 0.239913076 0.644987643
1403636938801666560 8.348193169 -2.486076832 6.513993740 0.036013622 0.725992143 0.237669796 0.644322515
1403636938851666432 8.319754601 -2.479558229 6.490524769 0.031251363 0.727518380 0.234248877 0.644102395
1403636938901666560 8.303313255 -2.478376865 6.471998215 0.023333244 0.729152441 0.231497198 0.643584788
1403636938951666432 8.280923843 -2.472293854 6.448728085 0.017033553 0.729931235 0.229940072 0.643457711
1403636939001666560 8.258254051 -2.461352348 6.425734520 0.011968990 0.731222332 0.226965502 0.643161952
1403636939051666432 8.228045464 -2.450548649 6.404938221 0.008387418 0.731645584 0.226133808 0.643030226
1403636939101666560 8.209495544 -2.448570490 6.375342846 0.007126688 0.731760383 0.224384263 0.643527508
1403636939151666432 8.187725067 -2.434953213 6.352517605 0.007737701 0.731768787 0.222488448 0.644168854
1403636939201666560 8.173463821 -2.432590008 6.332266808 0.008201361 0.732036412 0.221828431 0.644086659
1403636939251666432 8.148683548 -2.422046185 6.310932159 0.009308383 0.731953800 0.220707729 0.644550323
1403636939301666560 8.127777100 -2.406994581 6.291971207 0.010503085 0.731830657 0.219065920 0.645231485
1403636939351666432 8.106090546 -2.397527218 6.275938511 0.010859236 0.731659651 0.218071505 0.645756245
1403636939401666560 8.076495171 -2.372737169 6.251104832 0.011782035 0.730944693 0.216570929 0.647053361
1403636939451666432 8.054359436 -2.359753609 6.231665134 0.012336968 0.730570376 0.214921758 0.648014963
1403636939501666560 8.033833504 -2.351427555 6.209124565 0.013976329 0.730309069 0.212433591 0.649095714
1403636939551666432 8.011314392 -2.343003273 6.182771683 0.015818737 0.730417848 0.208620727 0.650166869
1403636939601666560 7.986888409 -2.341878891 6.164740086 0.017843172 0.731198370 0.204570785 0.650523841
1403636939651666432 7.968483448 -2.333490372 6.142467499 0.021797258 0.731353223 0.201820046 0.651088357
1403636939701666560 7.941269398 -2.325845718 6.112826347 0.024672410 0.730768621 0.201370686 0.651780903
1403636939751666432 7.915001869 -2.318198681 6.088712692 0.025073465 0.731115103 0.199389443 0.651986063
1403636939801666560 7.889373779 -2.313955307 6.066285610 0.025026854 0.731232643 0.199011922 0.651971400
1403636939851666432 7.862821579 -2.308673382 6.045203686 0.023866249 0.731218815 0.199790701 0.651792228
1403636939901666560 7.835992336 -2.301269531 6.013821125 0.024637597 0.730196774 0.203144655 0.651872635
1403636939951666432 7.810327530 -2.285846949 5.999453068 0.026380150 0.730726659 0.205477372 0.650478065
1403636940001666560 7.777635574 -2.274700642 5.975262165 0.026408888 0.732239485 0.207502604 0.648128510
1403636940051666432 7.743327141 -2.258231401 5.957448959 0.025466571 0.734463811 0.209553942 0.644981802
1403636940101666560 7.710217953 -2.249802113 5.937213421 0.024618860 0.736634731 0.212914079 0.641428769
1403636940151666432 7.684814453 -2.224251270 5.911010742 0.024242446 0.737773776 0.216429755 0.638952494
1403636940201666560 7.650083065 -2.214595795 5.892948151 0.023662109 0.739090204 0.219985098 0.636232972
1403636940251666432 7.605465889 -2.200812817 5.873855591 0.024225896 0.740476251 0.223172992 0.633483827
1403636940301666560 7.581178665 -2.172505379 5.845514297 0.024226373 0.741864383 0.222777233 0.631997347
1403636940351666432 7.542291164 -2.159620047 5.829002380 0.024367254 0.743671536 0.224089861 0.629398584
1403636940401666560 7.511113167 -2.135188580 5.805558681 0.025280386 0.744817019 0.224782571 0.627758980
1403636940451666432 7.484979153 -2.113535404 5.777365685 0.025740499 0.745828927 0.225507304 0.626277208
1403636940501666560 7.443542004 -2.098417282 5.762374401 0.025458917 0.747224212 0.227455869 0.623916388
1403636940551666432 7.406457424 -2.064970255 5.733514786 0.024496859 0.747553706 0.227620095 0.623500109
1403636940601666560 7.369728088 -2.044832468 5.705200195 0.020779615 0.747167587 0.231399715 0.622706175
1403636940651666432 7.347241402 -2.023778439 5.671835899 0.016080299 0.747576535 0.232581586 0.621913612
1403636940701666560 7.302130699 -2.018421650 5.655289650 0.011298777 0.748070359 0.235217005 0.620432138
1403636940751666432 7.266942024 -2.002939463 5.622539520 0.007654107 0.747821808 0.237191513 0.620035589
1403636940801666560 7.225424767 -1.993231297 5.604292870 0.004354709 0.748482704 0.238221809 0.618874013
1403636940851666432 7.195963860 -1.986178756 5.577114105 0.001429141 0.748850286 0.238914728 0.618175507
1403636940901666560 7.158392429 -1.978632331 5.548460484 -0.001572964 0.749127865 0.238999769 0.617805839
1403636940951666432 7.133094788 -1.975790977 5.511633396 -0.003133187 0.749098659 0.239692345 0.617567003
1403636941001666560 7.100755692 -1.970151663 5.481308937 -0.001496937 0.749638200 0.237209573 0.617876947
1403636941051666432 7.060697556 -1.967296958 5.455842972 -0.001441639 0.750521123 0.234035179 0.618015766
1403636941101666560 7.027403831 -1.967179060 5.426533699 0.000079462 0.751489222 0.231729299 0.617709816
1403636941151666432 7.000929832 -1.963246465 5.393239498 0.001523355 0.751641393 0.229415223 0.618386269
1403636941201666560 6.978310585 -1.964266062 5.361141682 0.001894021 0.751796603 0.228304535 0.618607581
1403636941251666432 6.945760727 -1.965982914 5.325958729 0.004675934 0.751688659 0.226926580 0.619230688
1403636941301666560 6.915599823 -1.969339848 5.298655510 0.006094510 0.752127886 0.224413663 0.619600713
1403636941351666432 6.885800362 -1.967016220 5.265808582 0.007014751 0.751873493 0.222360983 0.620638907
1403636941401666560 6.856958389 -1.962885499 5.237700462 0.007472428 0.751587152 0.220537469 0.621630251
1403636941451666432 6.827836990 -1.960055470 5.211285591 0.008036254 0.751240313 0.218842536 0.622640669
1403636941501666560 6.800371170 -1.956534266 5.183321953 0.008546125 0.750532091 0.218583643 0.623578131
1403636941551666432 6.776275635 -1.944695115 5.149291515 0.007852674 0.749624252 0.216933757 0.625253260
1403636941601666560 6.746152401 -1.937000871 5.125392914 0.007089579 0.748880923 0.216823205 0.626190722
1403636941651666432 6.715826988 -1.929934859 5.097635746 0.006813357 0.748127759 0.216615051 0.627165377
1403636941701666560 6.688472748 -1.921309114 5.072814941 0.005870589 0.747343481 0.216988355 0.627980292
1403636941751666432 6.661458015 -1.909149885 5.046364784 0.005482513 0.746803343 0.216301665 0.628862798
1403636941801666560 6.631576061 -1.903482676 5.022175789 0.005370819 0.745828211 0.217692643 0.629540563
1403636941851666432 6.602034569 -1.894325614 4.998553753 0.005373744 0.745362222 0.217480019 0.630165517
1403636941901666560 6.573092937 -1.889062285 4.973185539 0.004687007 0.744370997 0.219335407 0.630699456
1403636941951666432 6.545486450 -1.886195540 4.945826054 0.004113933 0.743526280 0.220182180 0.631404400
1403636942001666560 6.517755032 -1.882637143 4.920184612 0.005637695 0.742743433 0.221664414 0.631795287
1403636942051666432 6.490737915 -1.883100033 4.893942833 0.007745351 0.741964340 0.223500967 0.632041276
1403636942101666560 6.459828377 -1.880978465 4.865901947 0.008182853 0.741735935 0.223419085 0.632332802
1403636942151666432 6.430507183 -1.881178737 4.843692780 0.010034328 0.741937041 0.223589987 0.632009685
1403636942201666560 6.402480602 -1.880125046 4.814826965 0.011413150 0.741941929 0.223804638 0.631904483
1403636942251666432 6.372209549 -1.873883009 4.790678501 0.012535181 0.742003322 0.224216312 0.631665230
1403636942301666560 6.348329544 -1.869776368 4.762142181 0.014175468 0.741961122 0.225272268 0.631304324
1403636942351666432 6.315351486 -1.860330462 4.741027355 0.016355654 0.742440641 0.224908486 0.630817354
1403636942401666560 6.292065620 -1.855083108 4.710729122 0.018965304 0.742038310 0.227694646 0.630217910
1403636942451666432 6.266744137 -1.842286110 4.688271999 0.019724574 0.742150962 0.228610232 0.629730225
1403636942501666560 6.235211849 -1.837392211 4.660283566 0.020664403 0.741990626 0.232123137 0.628603101
1403636942551666432 6.209447861 -1.824888706 4.634126663 0.019641295 0.741644204 0.234871343 0.628023565
1403636942601666560 6.179891109 -1.810298324 4.609517574 0.018565129 0.742030144 0.236196905 0.627102554
1403636942651666432 6.152970314 -1.794103265 4.582963943 0.016452348 0.741910994 0.238139898 0.626567364
1403636942701666560 6.128207684 -1.778230190 4.552162170 0.012362647 0.742209077 0.238752514 0.626075208
1403636942751666432 6.102500916 -1.764450669 4.525985718 0.009718814 0.742795885 0.239540756 0.625124037
1403636942801666560 6.071442604 -1.747089624 4.503722668 0.008360152 0.743724406 0.238366663 0.624488115
1403636942851666432 6.046867847 -1.729725718 4.472156525 0.007267749 0.745254338 0.235685527 0.623695016
1403636942901666560 6.027941704 -1.717744946 4.438386440 0.007233856 0.746668816 0.232616901 0.623155534
1403636942951666432 5.992536068 -1.703331113 4.419592857 0.006529250 0.748983145 0.228218287 0.622011244
1403636943001666560 5.978113174 -1.696852088 4.376517773 0.007430821 0.749184489 0.228129819 0.621791065
1403636943051666432 5.953153610 -1.690244794 4.347258091 0.007479019 0.750616372 0.225096092 0.621168971
1403636943101666560 5.927178383 -1.688288927 4.315219879 0.008330481 0.751628876 0.224309921 0.620217383
1403636943151666432 5.901676178 -1.685245872 4.283594608 0.010104168 0.752314091 0.223620474 0.619608998
1403636943201666560 5.877221584 -1.675367355 4.251717567 0.011112386 0.753073633 0.222138152 0.619202077
1403636943251666432 5.855082512 -1.668712139 4.218921661 0.011251166 0.753443956 0.222428367 0.618644714
1403636943301666560 5.830465317 -1.660885334 4.188628197 0.010801055 0.754526854 0.221467227 0.617676914
1403636943351666432 5.803647995 -1.648767471 4.163856030 0.010648957 0.755890429 0.220049649 0.616517901
1403636943401666560 5.775063515 -1.639833093 4.137851715 0.011434251 0.756958425 0.219609275 0.615349472
1403636943451666432 5.751041889 -1.626857996 4.107387543 0.011327427 0.757503748 0.219503626 0.614717782
1403636943501666560 5.730226517 -1.614520907 4.076832771 0.011153555 0.758086205 0.218920976 0.614210486
1403636943551666432 5.704554081 -1.599282265 4.049100876 0.010841019 0.758540392 0.218839973 0.613683939
1403636943601666560 5.675619125 -1.579119682 4.027928352 0.010363307 0.759716630 0.216475338 0.613075554
1403636943651666432 5.652389050 -1.564342499 4.001343727 0.009465325 0.760516644 0.215900853 0.612300217
1403636943701666560 5.629031181 -1.545426846 3.977066755 0.011106956 0.761054277 0.215401113 0.611780524
1403636943751666432 5.603327274 -1.524278522 3.954576731 0.010512158 0.761570692 0.214977846 0.611297071
1403636943801666560 5.571208954 -1.506839514 3.931937933 0.008816053 0.761664748 0.214393079 0.611412108
1403636943851666432 5.546236038 -1.482916236 3.917440891 0.009211258 0.760641158 0.215361252 0.612339497
1403636943901666560 5.524271488 -1.458675861 3.898091316 0.007038252 0.757694304 0.217958808 0.615096509
1403636943951666432 5.490504265 -1.440456867 3.877710581 0.002619952 0.752594650 0.224202707 0.619134545
1403636944001666560 5.458650589 -1.413342476 3.858374834 -0.002763623 0.747395933 0.229353160 0.623529255
1403636944051666432 5.430939198 -1.389374256 3.845108747 -0.008475903 0.742999554 0.234634668 0.626758695
1403636944101666560 5.408617973 -1.370927095 3.822510719 -0.015128919 0.738002598 0.241416529 0.629953444
1403636944151666432 5.383124352 -1.347448945 3.808405876 -0.019335505 0.734740794 0.244407967 0.632492483
1403636944201666560 5.366770267 -1.330905914 3.786354780 -0.023228867 0.731956840 0.246199459 0.634890020
1403636944251666432 5.340054989 -1.312126279 3.770823956 -0.023079474 0.729940832 0.246778786 0.636988163
1403636944301666560 5.322745323 -1.298652530 3.750609159 -0.023233682 0.729119420 0.244491190 0.638802886
1403636944351666432 5.308168411 -1.287902832 3.730257511 -0.020172691 0.728766382 0.242017403 0.640250087
1403636944401666560 5.288484573 -1.273950100 3.707014561 -0.015832210 0.728700876 0.237435579 0.642159343
1403636944451666432 5.275246143 -1.267653227 3.691158056 -0.014267872 0.730608523 0.230015188 0.642729044
1403636944501666560 5.268890381 -1.261948228 3.662638426 -0.011506244 0.731585383 0.223083258 0.644115150
1403636944551666432 5.263090134 -1.264879107 3.644135952 -0.010872938 0.734039843 0.214323327 0.644307911
1403636944601666560 5.242425919 -1.246876478 3.612705946 -0.010773157 0.735815763 0.205161572 0.645265698
1403636944651666432 5.233175278 -1.247938871 3.595829487 -0.013094890 0.737265706 0.198412895 0.645678043
1403636944701666560 5.225272655 -1.249848843 3.581238747 -0.013916336 0.736900449 0.192793101 0.647776902
1403636944751666432 5.212265491 -1.252106905 3.561690331 -0.011915274 0.734419644 0.192866623 0.650606155
1403636944801666560 5.200056076 -1.248527288 3.547959089 -0.007391714 0.732288957 0.193566158 0.652863264
1403636944851666432 5.187571526 -1.256991148 3.530761480 -0.004541949 0.730088949 0.194734320 0.655002296
1403636944901666560 5.173959732 -1.265044808 3.518843174 -0.001907470 0.728272259 0.196524739 0.656501293
1403636944951666432 5.160731316 -1.274292588 3.502253056 0.000483477 0.726302326 0.197795749 0.658302069
1403636945001666560 5.152573109 -1.281165481 3.489877701 0.000978795 0.725066602 0.197997063 0.659601867
1403636945051666432 5.140963554 -1.280518174 3.483366489 0.001991985 0.724696219 0.197487220 0.660159230
1403636945101666560 5.125345230 -1.275008082 3.473574877 0.002486433 0.723982334 0.196595281 0.661206245
1403636945151666432 5.116154194 -1.275755048 3.463040590 0.002132620 0.722935677 0.197412163 0.662108719
1403636945201666560 5.103880882 -1.267941236 3.454888344 0.001831781 0.722215295 0.196710512 0.663103819
1403636945251666432 5.088303566 -1.263519168 3.449899673 0.002206397 0.721849144 0.196684524 0.663509011
1403636945301666560 5.076301575 -1.259814143 3.441998005 0.002020667 0.721261859 0.196971774 0.664062738
1403636945351666432 5.059554577 -1.256948233 3.439649105 0.002233636 0.721467435 0.196967080 0.663840115
1403636945401666560 5.043711185 -1.255857110 3.434662342 0.001324710 0.721543550 0.197065994 0.663730502
1403636945451666432 5.028232098 -1.256010294 3.428722620 0.001395549 0.721673250 0.196836039 0.663657546
1403636945501666560 5.008396149 -1.256977320 3.427967310 0.001699240 0.722227037 0.197020426 0.662999392
1403636945551666432 4.988792419 -1.255485892 3.425262928 0.001921258 0.721952140 0.199041188 0.662694454
1403636945601666560 4.972154140 -1.256868601 3.421466112 -0.000637754 0.721442044 0.202932090 0.662072182
1403636945651666432 4.956060886 -1.255894184 3.421144247 -0.005734637 0.720706522 0.207752541 0.661353230
1403636945701666560 4.940505028 -1.251799583 3.420477390 -0.011445222 0.719522178 0.214153171 0.660526514
1403636945751666432 4.926569462 -1.246638656 3.419951916 -0.017915703 0.718566477 0.219029978 0.659823596
1403636945801666560 4.907779217 -1.240303159 3.423006058 -0.023411989 0.717414796 0.224421471 0.659092486
1403636945851666432 4.891768456 -1.241514921 3.426438808 -0.027105555 0.717269599 0.227473781 0.658061743
1403636945901666560 4.878857136 -1.227689624 3.428104162 -0.025784651 0.717334747 0.228670463 0.657628894
1403636945951666432 4.868554592 -1.220164418 3.427973747 -0.023796631 0.718785942 0.224991277 0.657388270
1403636946001666560 4.862321854 -1.207868218 3.432340860 -0.018589888 0.721055090 0.219335496 0.656982481
1403636946051666432 4.851322651 -1.202587366 3.436113596 -0.013693796 0.723249793 0.214458227 0.656300187
1403636946101666560 4.843118191 -1.194119453 3.443374395 -0.012013942 0.724670351 0.212357968 0.655448377
1403636946151666432 4.835501671 -1.176138759 3.450968266 -0.009763394 0.725716412 0.210641161 0.654882133
1403636946201666560 4.834752083 -1.167059422 3.459664822 -0.008651564 0.726523280 0.210949585 0.653903186
1403636946251666432 4.824248314 -1.146919131 3.467236519 -0.007170368 0.727901638 0.208017081 0.653327286
1403636946301666560 4.817453384 -1.131149173 3.477066517 -0.004885616 0.729149103 0.206207275 0.652530670
1403636946351666432 4.815006256 -1.111957073 3.489899158 -0.004513160 0.730890274 0.203604639 0.651401639
1403636946401666560 4.808009624 -1.095198870 3.502099037 -0.001545602 0.731482744 0.203531429 0.650772989
1403636946451666432 4.803225517 -1.072170854 3.514646769 -0.000468041 0.732243776 0.203962684 0.649783075
1403636946501666560 4.796994209 -1.051826835 3.526657820 -0.000419070 0.732762635 0.203749195 0.649265110
1403636946551666432 4.790657043 -1.029619813 3.541118145 0.000650166 0.733652353 0.203259721 0.648412824
1403636946601666560 4.784904480 -1.009208798 3.554724932 0.000209178 0.734353065 0.203053430 0.647684276
1403636946651666432 4.775930405 -0.993030310 3.571929216 -0.000208405 0.734526575 0.205129117 0.646832824
1403636946701666560 4.770595551 -0.975839376 3.584289551 0.003601157 0.732666731 0.211244345 0.646963954
1403636946751666432 4.756840229 -0.958496571 3.600691557 0.011043764 0.730485737 0.219260097 0.646678925
1403636946801666560 4.754940033 -0.956172466 3.611866236 0.018249864 0.727835357 0.228448808 0.646323264
1403636946851666432 4.740672112 -0.936364055 3.626429558 0.023857320 0.726051688 0.233608440 0.646302402
1403636946901666560 4.732857227 -0.924440861 3.637500286 0.026785182 0.724681020 0.238454789 0.645956099
1403636946951666432 4.723019123 -0.909883618 3.647288084 0.032464545 0.722056687 0.245663181 0.645933151
1403636947001666560 4.712487221 -0.895375609 3.656933546 0.037897591 0.720391273 0.250678241 0.645569921
1403636947051666432 4.702000618 -0.878783822 3.662396431 0.039786872 0.719369948 0.254003078 0.645295501
1403636947101666560 4.694500446 -0.858971119 3.666871071 0.037145197 0.719592929 0.253827065 0.645273566
1403636947151666432 4.685774326 -0.840146780 3.671036720 0.029709913 0.721696258 0.250204593 0.644724369
1403636947201666560 4.674149513 -0.820707560 3.668351173 0.017336270 0.722835481 0.248236567 0.644660294
1403636947251666432 4.666097164 -0.807132006 3.662182808 0.002556809 0.723938406 0.246527895 0.644306302
1403636947301666560 4.656754971 -0.789361358 3.660280228 -0.010365128 0.724448502 0.246555090 0.643643856
1403636947351666432 4.651284218 -0.783269286 3.654781818 -0.020523053 0.724295855 0.248080149 0.642985642
1403636947401666560 4.646008015 -0.766429663 3.644147635 -0.027360592 0.723455727 0.249871671 0.642983198
1403636947451666432 4.643137455 -0.757697582 3.635921717 -0.031320922 0.723502994 0.250267118 0.642595291
1403636947501666560 4.643773079 -0.751425028 3.627042294 -0.028037068 0.723757267 0.250281096 0.642455220
1403636947551666432 4.649912834 -0.753298879 3.615468025 -0.022619402 0.724095166 0.250624001 0.642154217
1403636947601666560 4.656126499 -0.747442842 3.602064371 -0.016601767 0.725828469 0.245814398 0.642240345
1403636947651666432 4.662447929 -0.745125651 3.592515230 -0.014810887 0.727836907 0.240585104 0.641991317
1403636947701666560 4.663837433 -0.740740657 3.583741903 -0.013719475 0.729205072 0.236568630 0.641955614
1403636947751666432 4.674437523 -0.737838745 3.569034100 -0.015872320 0.730111539 0.232919410 0.642210007
1403636947801666560 4.682504177 -0.739544749 3.561210394 -0.018315503 0.731575131 0.229314685 0.641776562
1403636947851666432 4.692276478 -0.736855388 3.549860477 -0.023243509 0.733086467 0.223798141 0.641839862
1403636947901666560 4.706005573 -0.731393576 3.538111925 -0.027281115 0.734511614 0.218126640 0.642004073
1403636947951666432 4.714764595 -0.721816301 3.533230543 -0.028529227 0.735488355 0.214395061 0.642088473
1403636948001666560 4.730444908 -0.718722820 3.523998499 -0.028363043 0.734330356 0.217054605 0.642527640
1403636948051666432 4.743026257 -0.716677189 3.516167164 -0.028054288 0.732356012 0.221769840 0.643184006
1403636948101666560 4.757667065 -0.706571579 3.512964010 -0.028214501 0.730732322 0.225062475 0.643879652
1403636948151666432 4.776390076 -0.702856660 3.511409998 -0.029897986 0.730258465 0.225502163 0.644187450
1403636948201666560 4.792083740 -0.690224648 3.511038303 -0.029750090 0.730418205 0.223510787 0.644706964
1403636948251666432 4.813734055 -0.683265567 3.509544849 -0.030521134 0.730052054 0.222358063 0.645483851
1403636948301666560 4.834629059 -0.671092033 3.509323835 -0.030703351 0.730268598 0.220000431 0.646037757
1403636948351666432 4.857389927 -0.663609862 3.509654999 -0.031729557 0.730043054 0.218354315 0.646801174
1403636948401666560 4.876286030 -0.656018376 3.513834000 -0.033275861 0.730070114 0.216070861 0.647459388
1403636948451666432 4.896545410 -0.642486930 3.517487526 -0.034722090 0.729928732 0.213420004 0.648421347
1403636948501666560 4.919969559 -0.626647949 3.523530960 -0.038639102 0.731137216 0.206611976 0.649043024
1403636948551666432 4.945582867 -0.614941359 3.531730652 -0.043242022 0.732830524 0.198291242 0.649438202
1403636948601666560 4.966646194 -0.602613211 3.547197104 -0.046856426 0.734609425 0.190068603 0.649636269
1403636948651666432 4.995754242 -0.599678516 3.552050591 -0.049807124 0.735359371 0.184275851 0.650237083
1403636948701666560 5.029453278 -0.593865633 3.565122843 -0.047294363 0.735556483 0.181283250 0.651042402
1403636948751666432 5.058346272 -0.590002775 3.579874992 -0.041283049 0.734227538 0.183245093 0.652400851
1403636948801666560 5.088514805 -0.591161609 3.596395493 -0.031789739 0.731747508 0.188691303 0.654164016
1403636948851666432 5.113087654 -0.594964623 3.617274761 -0.022251686 0.729834497 0.193105415 0.655405879
1403636948901666560 5.136351585 -0.601792693 3.634974957 -0.012369935 0.727402031 0.197542921 0.657046437
1403636948951666432 5.167311668 -0.609546065 3.662554741 -0.001794831 0.725557029 0.202440023 0.657709539
1403636949001666560 5.192809582 -0.615209222 3.685578585 0.007865552 0.723714173 0.205163836 0.658850372
1403636949051666432 5.223458290 -0.625294447 3.704478264 0.012223435 0.721968293 0.207729578 0.659894526
1403636949101666560 5.243177891 -0.627858639 3.729374647 0.013468868 0.721974909 0.206057459 0.660387158
1403636949151666432 5.272774696 -0.632334828 3.746439934 0.012175440 0.721573055 0.205641970 0.660980642
1403636949201666560 5.290175915 -0.630450726 3.771673203 0.011531410 0.721521795 0.204088673 0.661529422
1403636949251666432 5.308341503 -0.633882880 3.801586151 0.008722753 0.722020984 0.202855542 0.661406994
1403636949301666560 5.335288048 -0.629906416 3.817059278 0.009455739 0.720887661 0.203596935 0.662404597
1403636949351666432 5.356251240 -0.631486773 3.839586735 0.012000831 0.719956040 0.205105111 0.662911117
1403636949401666560 5.374574661 -0.630636573 3.861372948 0.013413010 0.719135284 0.206337705 0.663392246
1403636949451666432 5.393902779 -0.628476143 3.886291504 0.015024967 0.718720555 0.207269341 0.663516700
1403636949501666560 5.412139893 -0.618572116 3.909588814 0.018015748 0.717985392 0.208163902 0.663957953
1403636949551666432 5.427512169 -0.616398573 3.935645103 0.020089116 0.717226088 0.210272640 0.664054692
1403636949601666560 5.442943096 -0.614623189 3.954615355 0.022066152 0.716433346 0.211619422 0.664419711
1403636949651666432 5.458118916 -0.606242061 3.977688074 0.021456173 0.715637147 0.213942572 0.664553702
1403636949701666560 5.475425720 -0.604175329 3.993792772 0.017885357 0.714960337 0.215783745 0.664792597
1403636949751666432 5.484243870 -0.598920822 4.011681557 0.013349501 0.714514792 0.216757238 0.665061474
1403636949801666560 5.499405861 -0.604577899 4.030929565 0.008689314 0.714099765 0.219053313 0.664832056
1403636949851666432 5.512328625 -0.609962225 4.045044422 0.005357333 0.712328792 0.224350572 0.665000558
1403636949901666560 5.524652958 -0.611428857 4.062092304 0.001207484 0.711864531 0.226148352 0.664909303
1403636949951666432 5.536150455 -0.615542889 4.075706482 -0.001684068 0.710918427 0.229033083 0.664933085
1403636950001666560 5.550865173 -0.621622562 4.087910652 -0.002656817 0.710197091 0.231892928 0.664709449
1403636950051666432 5.564045906 -0.630585313 4.099036694 -0.004667208 0.709440887 0.234597892 0.664556801
1403636950101666560 5.582201481 -0.634498000 4.111377716 -0.005100572 0.708915353 0.237164497 0.664203227
1403636950151666432 5.595465660 -0.643327951 4.120528698 -0.007436670 0.709210455 0.237124220 0.663880467
1403636950201666560 5.613224506 -0.639234781 4.130963802 -0.009708968 0.710078835 0.235070303 0.663653314
1403636950251666432 5.629163265 -0.648141980 4.140871525 -0.011963779 0.710799694 0.232946977 0.663593471
1403636950301666560 5.649692535 -0.646843195 4.149336338 -0.012296952 0.712154806 0.230800092 0.662884295
1403636950351666432 5.670406342 -0.650336266 4.158128262 -0.012491637 0.713375509 0.227469131 0.662719548
1403636950401666560 5.693813801 -0.647092462 4.168185711 -0.012092922 0.714930832 0.223255679 0.662483692
1403636950451666432 5.716335297 -0.649319768 4.176661491 -0.010635142 0.716303527 0.219150752 0.662396431
1403636950501666560 5.739276886 -0.645819187 4.186986923 -0.012479333 0.718395591 0.212859362 0.662150204
1403636950551666432 5.761354446 -0.642098308 4.196105957 -0.013449364 0.720304668 0.206748515 0.661993504
1403636950601666560 5.785371780 -0.639714718 4.208573818 -0.014919327 0.721892953 0.201839641 0.661746800
1403636950651666432 5.806587219 -0.638285279 4.222406387 -0.015264886 0.722606838 0.199421957 0.661692679
1403636950701666560 5.830909252 -0.640838146 4.233969688 -0.012618811 0.722266853 0.199505776 0.662094295
1403636950751666432 5.852225780 -0.644471407 4.248157024 -0.009423977 0.721925974 0.199815229 0.662425756
1403636950801666560 5.876507282 -0.649546862 4.260251999 -0.004302514 0.721033931 0.201119527 0.663055360
1403636950851666432 5.898962498 -0.656792283 4.275456905 -0.001370798 0.720045507 0.203124315 0.663530767
1403636950901666560 5.920254707 -0.661378026 4.287264347 0.000849520 0.719537258 0.203043118 0.664107561
1403636950951666432 5.943422318 -0.676350355 4.302692890 0.001315946 0.719190419 0.204374403 0.664074183
1403636951001666560 5.961821556 -0.682378292 4.317098141 0.003423044 0.718851924 0.204010427 0.664544880
1403636951051666432 5.981537819 -0.696357131 4.328248024 0.006358254 0.717925549 0.205782861 0.664978206
1403636951101666560 6.000636101 -0.704834580 4.342910290 0.009388035 0.716414988 0.209175706 0.665512562
1403636951151666432 6.019698620 -0.721994638 4.355420113 0.010715060 0.714214683 0.215832174 0.665731907
1403636951201666560 6.038156033 -0.731586576 4.367762089 0.008298915 0.712946951 0.219757169 0.665841281
1403636951251666432 6.062492371 -0.743346095 4.380244255 0.004389750 0.712235987 0.222837016 0.665615737
1403636951301666560 6.075109482 -0.741962075 4.390230656 -0.000558783 0.711312354 0.225110024 0.665852726
1403636951351666432 6.093478203 -0.742142677 4.405515194 -0.005482691 0.710773885 0.227443874 0.665612221
1403636951401666560 6.113110065 -0.752073884 4.417896748 -0.010485966 0.710034966 0.230239585 0.665379643
1403636951451666432 6.138888359 -0.757909775 4.436248779 -0.014319167 0.710494161 0.230592459 0.664695501
1403636951501666560 6.165629864 -0.751281857 4.439920425 -0.015606914 0.709690213 0.231679901 0.665147126
1403636951551666432 6.179903030 -0.753378391 4.454959869 -0.016519373 0.710465312 0.230573386 0.664681971
1403636951601666560 6.212988853 -0.750389576 4.463046551 -0.018671416 0.710588634 0.229715958 0.664790034
1403636951651666432 6.229209900 -0.757303357 4.478038788 -0.019060854 0.711527467 0.227150545 0.664656222
1403636951701666560 6.255052567 -0.758969069 4.496757030 -0.018610632 0.713251412 0.223367423 0.664103210
1403636951751666432 6.273176670 -0.770341516 4.504246235 -0.016462399 0.714058697 0.221898153 0.663784862
1403636951801666560 6.317737579 -0.757412791 4.514712811 -0.013834855 0.714798629 0.218435079 0.664197028
1403636951851666432 6.331429482 -0.772023320 4.539780617 -0.015533767 0.717264473 0.210947379 0.663921297
1403636951901666560 6.382884026 -0.762805700 4.540827751 -0.013893017 0.717433512 0.209686235 0.664174497
1403636951951666432 6.402783394 -0.775902390 4.544349670 -0.015610442 0.718686521 0.206313282 0.663837969
1403636952001666560 6.429994583 -0.786911011 4.562159061 -0.016493721 0.719745159 0.204003140 0.663383484
1403636952051666432 6.448470592 -0.791373968 4.571360588 -0.016386792 0.720602453 0.200998828 0.663372457
1403636952101666560 6.482742310 -0.806322455 4.590171814 -0.014206235 0.720911026 0.201115802 0.663051903
1403636952151666432 6.516569138 -0.811422944 4.604981899 -0.011393294 0.720472336 0.202416435 0.663187265
1403636952201666560 6.540640354 -0.814466000 4.624722481 -0.007610339 0.720778465 0.201536372 0.663176835
1403636952251666432 6.573346138 -0.819922686 4.640969276 -0.003081378 0.720331252 0.202416137 0.663431287
1403636952301666560 6.602408409 -0.826046586 4.660000801 0.002774737 0.719521224 0.205110684 0.663484037
1403636952351666432 6.629302979 -0.817770004 4.678070545 0.008506621 0.719049931 0.204870760 0.664020181
1403636952401666560 6.657580853 -0.817078948 4.696191788 0.011559940 0.718531370 0.205683783 0.664283931
1403636952451666432 6.686734200 -0.820404053 4.717959881 0.012707087 0.718850791 0.204826355 0.664182425
1403636952501666560 6.714274406 -0.813914776 4.739492416 0.011825413 0.719303548 0.202574492 0.664399087
1403636952551666432 6.736881733 -0.804039836 4.755797386 0.009537784 0.719818473 0.200151235 0.664612591
1403636952601666560 6.761518478 -0.799488425 4.778453827 0.008856975 0.720466435 0.198500305 0.664415002
1403636952651666432 6.786040783 -0.797835827 4.796507359 0.008507289 0.720632792 0.197479174 0.664543450
1403636952701666560 6.808041573 -0.797168136 4.818253994 0.007134638 0.720872700 0.195911527 0.664763391
1403636952751666432 6.837380886 -0.786203027 4.828466892 0.006030995 0.719526827 0.198681787 0.665409923
1403636952801666560 6.856637001 -0.793453217 4.860466480 0.001812977 0.719508946 0.201554134 0.664589703
1403636952851666432 6.875194550 -0.800900102 4.879279137 -0.000647777 0.718682706 0.204844221 0.664479971
1403636952901666560 6.896053791 -0.800983548 4.896522045 -0.001693067 0.717396200 0.209455565 0.664430678
1403636952951666432 6.922928810 -0.788556457 4.906691551 -0.002703928 0.714960814 0.215182856 0.665221810
1403636953001666560 6.947418213 -0.793887973 4.930023670 -0.001554224 0.713354409 0.221617922 0.664837241
1403636953051666432 6.958800793 -0.802760363 4.954132557 -0.000204096 0.712251782 0.227512166 0.664029837
1403636953101666560 6.990036488 -0.785772562 4.970714092 0.003021491 0.710780978 0.230879724 0.664436460
1403636953151666432 7.001995087 -0.794837236 4.995263577 0.002626673 0.710553408 0.233071968 0.663915992
1403636953201666560 7.023835182 -0.773694277 5.021781445 0.002798381 0.710657716 0.231064871 0.664504945
1403636953251666432 7.049904823 -0.778300047 5.030554295 0.002133794 0.709986210 0.235015079 0.663839579
1403636953301666560 7.079551697 -0.764484644 5.043105125 0.002120424 0.709762871 0.233597293 0.664578378
1403636953351666432 7.114908218 -0.743348122 5.058784008 0.001547975 0.709411263 0.232965022 0.665177107
1403636953401666560 7.119884491 -0.754033804 5.068427563 -0.000583208 0.711112082 0.228469461 0.664921761
1403636953451666432 7.143492699 -0.750028372 5.094566822 -0.001614974 0.712636530 0.224461213 0.664653122
1403636953501666560 7.191387653 -0.730285168 5.099244118 -0.003503609 0.712876737 0.218916282 0.666235805
1403636953551666432 7.194585800 -0.733736992 5.117586136 -0.003651210 0.714326560 0.214981958 0.665963173
1403636953601666560 7.220883846 -0.728453159 5.124205112 -0.006470647 0.714503646 0.212296695 0.666612923
1403636953651666432 7.239472389 -0.735807180 5.135430336 -0.010452176 0.714667201 0.211434603 0.666661084
1403636953701666560 7.269290924 -0.734081507 5.150252819 -0.015115514 0.714399397 0.209909394 0.667340279
1403636953751666432 7.296115398 -0.745301723 5.158006191 -0.018843053 0.714207113 0.210425526 0.667288721
1403636953801666560 7.320306301 -0.759240389 5.173224449 -0.023801906 0.714823961 0.207187802 0.667482853
1403636953851666432 7.342288971 -0.764004230 5.176829815 -0.024727503 0.714890182 0.205352440 0.667945266
1403636953901666560 7.330546856 -0.787188530 5.187084198 -0.023489853 0.714991510 0.204063401 0.668276548
1403636953951666432 7.357325554 -0.810601950 5.199561119 -0.022481607 0.714145839 0.205317572 0.668831050
1403636954001666560 7.397798061 -0.831354141 5.221410751 -0.020899326 0.713687658 0.208353624 0.668432415
1403636954051666432 7.431461811 -0.834531307 5.226114750 -0.018188395 0.712512851 0.210047677 0.669234276
1403636954101666560 7.469805717 -0.839452744 5.229626179 -0.016975047 0.711679280 0.210687310 0.669951677
1403636954151666432 7.488360405 -0.861003399 5.247598648 -0.015765885 0.711965263 0.210942939 0.669596851
1403636954201666560 7.531947136 -0.867702723 5.274080276 -0.015107875 0.711762607 0.211229265 0.669737220
1403636954251666432 7.567982197 -0.867167234 5.291134357 -0.015969239 0.711320162 0.211650595 0.670054197
1403636954301666560 7.595581055 -0.879074335 5.311317921 -0.016431659 0.711240590 0.212943494 0.669717789
1403636954351666432 7.618781090 -0.897637606 5.331515789 -0.016092356 0.711488903 0.214086756 0.669097543
1403636954401666560 7.668181419 -0.908306599 5.367964268 -0.019124037 0.711760879 0.214065671 0.668735087
1403636954451666432 7.698488235 -0.927442551 5.361320972 -0.017897667 0.710834026 0.218473479 0.668329298
1403636954501666560 7.728459358 -0.941282511 5.383642673 -0.018801153 0.711070478 0.219155163 0.667829514
1403636954551666432 7.781215668 -0.942593098 5.399569035 -0.018270154 0.711400092 0.219338119 0.667433083
1403636954601666560 7.801635265 -0.958621264 5.417808533 -0.019797495 0.712877393 0.217671305 0.666358113
1403636954651666432 7.843509674 -0.979548216 5.451107979 -0.020174555 0.714988649 0.215665594 0.664734960
1403636954701666560 7.877278328 -0.980644226 5.466981411 -0.017293002 0.716326237 0.214303955 0.663815916
1403636954751666432 7.913913727 -0.986754656 5.488863945 -0.013691732 0.717936039 0.212875023 0.662619472
1403636954801666560 7.954505920 -0.987234354 5.515585899 -0.010980843 0.719972193 0.209467277 0.661545813
1403636954851666432 7.989264488 -0.990316153 5.537570000 -0.008489845 0.721898675 0.207880944 0.659981668
1403636954901666560 8.026240349 -0.997152328 5.569447517 -0.005547318 0.723801076 0.206998244 0.658204377
1403636954951666432 8.065322876 -0.987801790 5.589992046 -0.002152199 0.724918723 0.206516340 0.657144725
1403636955001666560 8.102807999 -0.986022949 5.608335018 -0.001656499 0.726095080 0.204610646 0.656443238
1403636955051666432 8.126587868 -0.992848158 5.646244526 -0.002244717 0.728467166 0.205718830 0.653460205
1403636955101666560 8.172725677 -0.989352465 5.674974918 -0.004177457 0.729785860 0.205507264 0.652044415
1403636955151666432 8.203872681 -0.996208429 5.694584370 -0.005462577 0.731212258 0.206318811 0.650178015
1403636955201666560 8.231446266 -1.003822327 5.741164207 -0.007163229 0.733831346 0.204800799 0.647685707
1403636955251666432 8.252608299 -1.016675234 5.763073921 -0.006235617 0.735043108 0.206290931 0.645845830
1403636955301666560 8.294115067 -1.002195120 5.778952599 -0.004568202 0.735842109 0.205540717 0.645188749
1403636955351666432 8.341047287 -1.009593248 5.809462547 -0.005172743 0.737361908 0.205406517 0.643489599
1403636955401666560 8.369617462 -1.019366741 5.833859444 -0.004431041 0.738510668 0.205532134 0.642136216
1403636955451666432 8.424240112 -1.018953800 5.864466667 -0.004799283 0.739523411 0.205798924 0.640881360
1403636955501666560 8.461860657 -1.032636404 5.895102501 -0.005022926 0.740333259 0.207530618 0.639384389
1403636955551666432 8.497572899 -1.040537357 5.918975353 -0.005913411 0.740898073 0.207751825 0.638650358
1403636955601666560 8.536922455 -1.051662207 5.958552361 -0.005866410 0.741863489 0.209146768 0.637072861
1403636955651666432 8.561237335 -1.056652308 5.977110386 -0.006312583 0.742281377 0.208792731 0.636697829
1403636955701666560 8.590596199 -1.060765266 6.014420986 -0.006387978 0.743387997 0.208829135 0.635392785
1403636955751666432 8.617923737 -1.059086323 6.040996552 -0.005748219 0.743211091 0.208746284 0.635632873
1403636955801666560 8.652108192 -1.065023184 6.072513103 -0.006013070 0.743825853 0.208469450 0.635001898
1403636955851666432 8.682665825 -1.076598406 6.101418495 -0.005571641 0.743520737 0.210176945 0.634800375
1403636955901666560 8.713914871 -1.089470863 6.134654522 -0.002529721 0.743148565 0.212841451 0.634367645
1403636955951666432 8.744874001 -1.100648165 6.165554523 0.001729253 0.742150903 0.216938540 0.634150386
1403636956001666560 8.770233154 -1.113700390 6.197931290 0.007972441 0.741143227 0.220925704 0.633904517
1403636956051666432 8.798814774 -1.131088972 6.227103233 0.014454408 0.740255058 0.225106180 0.633356750
1403636956101666560 8.827258110 -1.159211874 6.249469757 0.018785119 0.738948107 0.229423746 0.633219957
1403636956151666432 8.864108086 -1.173270941 6.273211002 0.021786658 0.737880409 0.232953444 0.633080184
1403636956201666560 8.892301559 -1.186921835 6.301899910 0.024904409 0.737858832 0.235002801 0.632232308
1403636956251666432 8.918885231 -1.201494217 6.324295044 0.025622981 0.738018811 0.235901073 0.631682277
1403636956301666560 8.940343857 -1.209245205 6.353055954 0.022878028 0.739464462 0.233905584 0.630838454
1403636956351666432 8.971912384 -1.220741510 6.373785496 0.016548811 0.741900623 0.229089484 0.629942536
1403636956401666560 8.995371819 -1.224556923 6.399808884 0.010738304 0.743729949 0.225070357 0.629359901
1403636956451666432 9.019447327 -1.233846903 6.423114300 0.005700490 0.745494246 0.220359907 0.629005015
1403636956501666560 9.045274734 -1.239519119 6.447936535 0.002510560 0.746247053 0.216391757 0.629510701
1403636956551666432 9.072759628 -1.246736050 6.474279404 0.004319045 0.745640278 0.212116316 0.631671250
1403636956601666560 9.097973824 -1.246531487 6.498207092 0.008867654 0.742826879 0.209435314 0.635819495
1403636956651666432 9.117658615 -1.251882076 6.524695873 0.014730092 0.738321424 0.208820522 0.641138434
1403636956701666560 9.142554283 -1.255744457 6.552863121 0.021073146 0.731793225 0.210427582 0.647884905
1403636956751666432 9.156989098 -1.254496336 6.584446907 0.025228877 0.724056363 0.212173700 0.655811131
1403636956801666560 9.180759430 -1.259514332 6.604676723 0.028902814 0.714862466 0.215222552 0.664692044
1403636956851666432 9.201076508 -1.266758680 6.626592159 0.028391732 0.704733908 0.215956628 0.675208688
1403636956901666560 9.219168663 -1.268378496 6.652840614 0.026751798 0.695305467 0.214506820 0.685435176
1403636956951666432 9.230683327 -1.281510353 6.680849552 0.022731166 0.686728895 0.209123388 0.695811808
1403636957001666560 9.248467445 -1.277911663 6.701444149 0.020210104 0.677411854 0.202785611 0.706811666
1403636957051666432 9.266716003 -1.298296452 6.716522694 0.015484578 0.667784929 0.196598023 0.717755377
1403636957101666560 9.278181076 -1.304037809 6.736692429 0.011493330 0.658236206 0.188411847 0.728761971
1403636957151666432 9.290702820 -1.314615965 6.746188164 0.007011611 0.647795677 0.182038024 0.739711940
1403636957201666560 9.302583694 -1.327338457 6.765387535 0.003642945 0.638862729 0.176304847 0.748837590
1403636957251666432 9.311035156 -1.338932991 6.780484200 0.002203489 0.630119264 0.171801254 0.757251084
1403636957301666560 9.320337296 -1.351312637 6.797427654 0.000489537 0.622748792 0.169113442 0.763926923
1403636957351666432 9.334166527 -1.363797188 6.810274601 -0.000496523 0.616122603 0.166677088 0.769812644
1403636957401666560 9.340060234 -1.372286081 6.824274540 -0.000195789 0.610422552 0.165236518 0.774649084
1403636957451666432 9.354036331 -1.382647514 6.840085030 -0.000772578 0.605617702 0.164338052 0.778601050
1403636957501666560 9.364782333 -1.388581753 6.850547791 0.000352613 0.601413965 0.164360106 0.781848371
1403636957551666432 9.373209000 -1.392671585 6.863617420 0.000791818 0.597603738 0.164836287 0.784664333
1403636957601666560 9.380221367 -1.392861128 6.880434036 0.002173405 0.593447626 0.163431078 0.788102448
1403636957651666432 9.394181252 -1.391228080 6.900005341 0.003254826 0.588671625 0.162891701 0.791783750
1403636957701666560 9.398812294 -1.393257022 6.921837807 0.003436453 0.583652496 0.161750600 0.795722783
1403636957751666432 9.409717560 -1.393092990 6.941041946 0.003711504 0.576347888 0.161545783 0.801069438
1403636957801666560 9.416275978 -1.389065027 6.953788757 0.003840049 0.566525340 0.160969779 0.808160245
1403636957851666432 9.422022820 -1.387447238 6.972337246 0.003606863 0.555517435 0.159528568 0.816050231
1403636957901666560 9.432482719 -1.379130840 6.987594604 0.003660865 0.542729795 0.156436682 0.825202107
1403636957951666432 9.440179825 -1.371330261 7.006398201 0.003023278 0.529836237 0.151951954 0.834371030
1403636958001666560 9.443164825 -1.369524598 7.026278019 0.002888092 0.516061842 0.148086369 0.843648195
1403636958051666432 9.452147484 -1.365669608 7.028084278 0.002815821 0.500635624 0.145084053 0.853408813
1403636958101666560 9.463928223 -1.369259477 7.054395199 0.000375128 0.488369226 0.139348239 0.861439168
1403636958151666432 9.464744568 -1.371397972 7.065413475 -0.001822469 0.476504773 0.134061590 0.868888557
1403636958201666560 9.481145859 -1.370669007 7.078491211 -0.002875927 0.464949489 0.130617604 0.875644147
1403636958251666432 9.477212906 -1.380868912 7.087319374 -0.003098530 0.455206186 0.127312422 0.881231666
1403636958301666560 9.481530190 -1.389091730 7.107671738 -0.003218117 0.446315914 0.121983089 0.886516750
1403636958351666432 9.497709274 -1.392761111 7.113365173 -0.005246897 0.436631262 0.117661275 0.891897678
1403636958401666560 9.503787994 -1.403855801 7.128917694 -0.007302184 0.430170447 0.113002047 0.895617425
1403636958451666432 9.514774323 -1.416838169 7.127437592 -0.008581246 0.423726588 0.110368632 0.898999929
1403636958501666560 9.523292542 -1.423960090 7.136197567 -0.010556955 0.419109583 0.107073881 0.901538074
1403636958551666432 9.530251503 -1.436307311 7.130055428 -0.011495218 0.415250510 0.104883365 0.903567553
1403636958601666560 9.537448883 -1.447144151 7.139755249 -0.011816023 0.412893444 0.103667863 0.904783010
1403636958651666432 9.547215462 -1.449717402 7.149507046 -0.011961682 0.411494732 0.101896420 0.905619204
1403636958701666560 9.558704376 -1.457696438 7.152483463 -0.011861417 0.410617948 0.100423180 0.906182885
1403636958751666432 9.577085495 -1.458567619 7.163228035 -0.011730507 0.410283566 0.099528410 0.906434715
1403636958801666560 9.574052811 -1.466982841 7.168685913 -0.011501529 0.410670191 0.099900290 0.906221628
1403636958851666432 9.586639404 -1.475365877 7.174861431 -0.012227663 0.410851747 0.100018516 0.906116784
1403636958901666560 9.599474907 -1.479889870 7.181486130 -0.013802451 0.411967963 0.099801764 0.905611098
1403636958951666432 9.610672951 -1.488325834 7.191133499 -0.014790446 0.413422644 0.099069476 0.905012786
1403636959001666560 9.629427910 -1.483385563 7.190985680 -0.014802968 0.413902342 0.099388368 0.904758334
1403636959051666432 9.632143974 -1.480455399 7.200347900 -0.015185283 0.415606946 0.099588282 0.903948247
1403636959101666560 9.636610031 -1.477413535 7.222368240 -0.015759004 0.417450160 0.100039288 0.903038800
1403636959151666432 9.649154663 -1.476143241 7.219286919 -0.015882390 0.417644620 0.101972423 0.902730465
1403636959201666560 9.662704468 -1.478266716 7.235027313 -0.016581351 0.419246137 0.102766395 0.901885152
1403636959251666432 9.678972244 -1.472588658 7.243707180 -0.016421938 0.420010000 0.101776287 0.901644886
1403636959301666560 9.685306549 -1.463035583 7.262608051 -0.017434534 0.422895283 0.098709501 0.900617599
1403636959351666432 9.704330444 -1.452120423 7.275800705 -0.018997485 0.424568057 0.095250934 0.900171280
1403636959401666560 9.714241028 -1.443529725 7.287674904 -0.019368174 0.425928414 0.094072334 0.899644554
1403636959451666432 9.721069336 -1.439078569 7.308626175 -0.019658264 0.427827805 0.091671444 0.898984611
1403636959501666560 9.733377457 -1.421658754 7.327713490 -0.017615102 0.429213911 0.089992106 0.898535788
1403636959551666432 9.746608734 -1.413604736 7.339987755 -0.012997662 0.428527355 0.092582121 0.898679018
1403636959601666560 9.755679131 -1.400051236 7.355367661 -0.007162778 0.428019971 0.094277687 0.898809910
1403636959651666432 9.762295723 -1.391960979 7.365647316 -0.005921257 0.427696556 0.095367588 0.898857951
1403636959701666560 9.767628670 -1.387940049 7.384709358 -0.006984516 0.428265661 0.097977161 0.898298502
1403636959751666432 9.778806686 -1.384829521 7.407440186 -0.007653446 0.428409517 0.099844165 0.898018837
1403636959801666560 9.784854889 -1.384257555 7.418029308 -0.009239988 0.428284347 0.101243012 0.897907019
1403636959851666432 9.793791771 -1.379050255 7.431541443 -0.009179237 0.428375602 0.102862291 0.897680044
1403636959901666560 9.796918869 -1.381386518 7.447304249 -0.010791327 0.429323822 0.103868254 0.897093058
1403636959951666432 9.803380966 -1.387321234 7.460520744 -0.011775819 0.429518282 0.104087010 0.896962225
1403636960001666560 9.807579994 -1.392573476 7.473770618 -0.011654856 0.429788709 0.104792990 0.896752059
1403636960051666432 9.813281059 -1.398521781 7.482692719 -0.011565136 0.429775685 0.105302975 0.896699727
1403636960101666560 9.817652702 -1.403952360 7.498196125 -0.010945158 0.429962546 0.104754828 0.896682143
1403636960151666432 9.823896408 -1.410592556 7.508862972 -0.011502429 0.430571496 0.103284851 0.896553457
1403636960201666560 9.828527451 -1.421174526 7.522231102 -0.012378638 0.431175530 0.102114297 0.896385610
1403636960251666432 9.832479477 -1.428798199 7.536118984 -0.015594970 0.433317453 0.096193738 0.895957351
1403636960301666560 9.841242790 -1.429666519 7.547092915 -0.017228197 0.434187859 0.093035795 0.895839512
1403636960351666432 9.842147827 -1.438983440 7.565773010 -0.019111557 0.435621172 0.089546911 0.895460963
1403636960401666560 9.849925041 -1.442603707 7.576491356 -0.017483968 0.435940206 0.086911060 0.895598650
1403636960451666432 9.852966309 -1.447134852 7.591469288 -0.015509899 0.435147285 0.083901763 0.896307290
1403636960501666560 9.854376793 -1.444922805 7.613028526 -0.013225881 0.433852047 0.080402873 0.897291958
1403636960551666432 9.858026505 -1.447782278 7.629541397 -0.012271419 0.431664020 0.076942869 0.898663104
1403636960601666560 9.856656075 -1.447270155 7.651661873 -0.011223864 0.429745704 0.073380455 0.899893284
1403636960651666432 9.858292580 -1.447962523 7.669905663 -0.009535144 0.426510751 0.072366320 0.901532471
1403636960701666560 9.853569031 -1.444798112 7.690950394 -0.007465001 0.422901064 0.075606063 0.902985394
1403636960751666432 9.852036476 -1.447699785 7.708602905 -0.006533241 0.418108970 0.081970640 0.904667377
1403636960801666560 9.846452713 -1.443708420 7.731155872 -0.006481051 0.412782133 0.086292006 0.906709731
1403636960851666432 9.841215134 -1.436949492 7.757349968 -0.006106249 0.406164229 0.088645808 0.909469783
1403636960901666560 9.836601257 -1.434540868 7.776248455 -0.006999474 0.397554815 0.089318372 0.913194060
1403636960951666432 9.828334808 -1.429539680 7.795987129 -0.007819843 0.387981921 0.087728739 0.917448938
1403636961001666560 9.815742493 -1.428262830 7.824683189 -0.007986339 0.378127486 0.083634093 0.921933353
1403636961051666432 9.811517715 -1.430277348 7.849728107 -0.008355480 0.366556406 0.079412550 0.926962912
1403636961101666560 9.800242424 -1.428228855 7.868021965 -0.008201958 0.354295790 0.075864360 0.932014942
1403636961151666432 9.789665222 -1.436088443 7.880910873 -0.008323139 0.341104001 0.072332270 0.937201560
1403636961201666560 9.783004761 -1.433475733 7.904839516 -0.008376402 0.327895582 0.067896970 0.942233682
1403636961251666432 9.767791748 -1.433557987 7.922935009 -0.008160627 0.314832300 0.064769059 0.946899652
1403636961301666560 9.758770943 -1.451963902 7.938185692 -0.010446448 0.303228796 0.060017943 0.950968504
1403636961351666432 9.750259399 -1.452950001 7.958085537 -0.009425900 0.292871684 0.054995492 0.954522312
1403636961401666560 9.738385201 -1.468793154 7.971101761 -0.010310831 0.283931136 0.051382091 0.957411468
1403636961451666432 9.732491493 -1.477229834 7.983601093 -0.009938100 0.275499433 0.048556872 0.960022688
1403636961501666560 9.719591141 -1.486479759 7.998963356 -0.009944904 0.268801332 0.047219288 0.961986125
1403636961551666432 9.707664490 -1.501134396 8.017095566 -0.009956644 0.261657804 0.044264756 0.964093685
1403636961601666560 9.704296112 -1.518822670 8.023746490 -0.009906492 0.252708584 0.043298196 0.966522396
1403636961651666432 9.689428329 -1.529560208 8.037374496 -0.008734114 0.244492501 0.040870965 0.968750119
1403636961701666560 9.677450180 -1.556166649 8.048453331 -0.009009692 0.236374915 0.037951495 0.970878661
1403636961751666432 9.661193848 -1.574908853 8.062125206 -0.008822061 0.228204429 0.034495402 0.972961962
1403636961801666560 9.656563759 -1.593970060 8.069797516 -0.008650173 0.218772471 0.030652717 0.975255907
1403636961851666432 9.641925812 -1.613714337 8.074106216 -0.010589217 0.209795550 0.027156981 0.977310717
1403636961901666560 9.629741669 -1.631568789 8.086046219 -0.010584150 0.200659588 0.022236954 0.979351461
1403636961951666432 9.616375923 -1.645397663 8.097777367 -0.009661383 0.190152347 0.019250991 0.981518269
1403636962001666560 9.601769447 -1.656362057 8.111881256 -0.010545327 0.180169702 0.015670586 0.983454168
1403636962051666432 9.598503113 -1.669493914 8.112806320 -0.011737482 0.168096021 0.012603982 0.985620201
1403636962101666560 9.582108498 -1.678506613 8.127461433 -0.012508590 0.157808945 0.008720351 0.987351954
1403636962151666432 9.566827774 -1.691141367 8.141138077 -0.013074785 0.146926209 0.004663630 0.989050031
1403636962201666560 9.557794571 -1.702840090 8.146325111 -0.012960117 0.134989753 0.001200590 0.990761518
1403636962251666432 9.537235260 -1.719945908 8.160816193 -0.012197098 0.124539562 -0.003976678 0.992131710
1403636962301666560 9.525721550 -1.731026292 8.170677185 -0.011889337 0.112744518 -0.008579188 0.993515849
1403636962351666432 9.509394646 -1.746481776 8.173971176 -0.011672954 0.100300193 -0.011522024 0.994822025
1403636962401666560 9.493238449 -1.767704010 8.179158211 -0.012055489 0.088631824 -0.016886100 0.995848358
1403636962451666432 9.483679771 -1.788897395 8.183589935 -0.012509889 0.076008067 -0.021997368 0.996785998
1403636962501666560 9.468030930 -1.807756186 8.186186790 -0.012529301 0.064797550 -0.028768213 0.997404993
1403636962551666432 9.454312325 -1.827908993 8.189194679 -0.012766022 0.052881777 -0.036057204 0.997867942
1403636962601666560 9.438561440 -1.847423077 8.195033073 -0.013601800 0.041479066 -0.044174839 0.998069644
1403636962651666432 9.420048714 -1.868518114 8.195712090 -0.014004097 0.031444211 -0.052069966 0.998050034
1403636962701666560 9.405797958 -1.890336871 8.192930222 -0.014143291 0.021626906 -0.060718939 0.997820377
1403636962751666432 9.388914108 -1.906777143 8.194079399 -0.013578015 0.014049180 -0.066789195 0.997575760
1403636962801666560 9.363684654 -1.921148181 8.203294754 -0.014133109 0.008079629 -0.071084216 0.997337461
1403636962851666432 9.347944260 -1.935360551 8.202208519 -0.013141525 0.002008025 -0.074543364 0.997129142
1403636962901666560 9.323477745 -1.944854736 8.211699486 -0.012411758 -0.002516776 -0.073493086 0.997215331
1403636962951666432 9.299542427 -1.956576943 8.219231606 -0.011489883 -0.006760388 -0.070452377 0.997426033
1403636963001666560 9.269799232 -1.963039517 8.229418755 -0.006710912 -0.009660740 -0.067565545 0.997645497
1403636963051666432 9.250396729 -1.972693086 8.233275414 -0.001384176 -0.012592578 -0.064303435 0.997850001
1403636963101666560 9.229022980 -1.979732871 8.230359077 0.002962199 -0.014681038 -0.061123222 0.998017848
1403636963151666432 9.200837135 -1.987528563 8.230808258 0.004191095 -0.014800622 -0.059041847 0.998136938
1403636963201666560 9.176418304 -1.989298701 8.234772682 0.003712831 -0.014440818 -0.057960138 0.998207569
1403636963251666432 9.149265289 -1.993299127 8.237043381 0.000078047 -0.014111646 -0.054343354 0.998422623
1403636963301666560 9.130619049 -1.988127708 8.236141205 -0.002473405 -0.014736544 -0.050071258 0.998633862
1403636963351666432 9.098499298 -1.987827301 8.240252495 -0.005174055 -0.013543325 -0.045751639 0.998847604
1403636963401666560 9.073819160 -1.983492017 8.234436989 -0.006464678 -0.012616055 -0.043194141 0.998966098
1403636963451666432 9.051744461 -1.980203152 8.238382339 -0.007865478 -0.010941587 -0.042785916 0.998993397
1403636963501666560 9.023622513 -1.976894021 8.233946800 -0.008672113 -0.008331171 -0.043800477 0.998967886
1403636963551666432 9.003004074 -1.973099709 8.235353470 -0.008458557 -0.006664431 -0.043664914 0.998988211
1403636963601666560 8.977436066 -1.972827673 8.231662750 -0.008766963 -0.004372844 -0.044971917 0.998940229
1403636963651666432 8.943166733 -1.975016117 8.231443405 -0.009656744 -0.001064912 -0.045261264 0.998927951
1403636963701666560 8.921249390 -1.977254987 8.224651337 -0.009793700 0.000929807 -0.045720320 0.998905838
1403636963751666432 8.895606995 -1.981572151 8.217059135 -0.010012982 0.002734015 -0.045462359 0.998912156
1403636963801666560 8.870310783 -1.986989021 8.212387085 -0.010431545 0.004536321 -0.045289211 0.998909175
1403636963851666432 8.842797279 -1.990934730 8.203878403 -0.009595502 0.006005548 -0.045435529 0.998903155
1403636963901666560 8.816999435 -1.998862743 8.195075035 -0.008867444 0.007395893 -0.045655698 0.998890460
1403636963951666432 8.793632507 -2.007104397 8.185966492 -0.008267052 0.008174026 -0.044540823 0.998939931
1403636964001666560 8.767182350 -2.019795656 8.171462059 -0.008215279 0.008780120 -0.045022216 0.998913646
1403636964051666432 8.741739273 -2.032339573 8.160734177 -0.007665466 0.008817860 -0.044555638 0.998938560
1403636964101666560 8.708416939 -2.042882442 8.151494980 -0.007293996 0.009887927 -0.045844663 0.998872995
1403636964151666432 8.683943748 -2.054663181 8.136803627 -0.006448744 0.009225512 -0.046523198 0.998853743
1403636964201666560 8.659536362 -2.064576387 8.122062683 -0.004551641 0.008819601 -0.046656903 0.998861670
1403636964251666432 8.626443863 -2.072462559 8.111127853 -0.004494175 0.008815728 -0.046862941 0.998852313
1403636964301666560 8.604646683 -2.082384825 8.095306396 -0.005314617 0.008554908 -0.049005378 0.998747766
1403636964351666432 8.570405006 -2.089261293 8.082833290 -0.004909046 0.008444009 -0.049557827 0.998723507
1403636964401666560 8.544455528 -2.092473030 8.071253777 -0.004813389 0.008374552 -0.051438630 0.998629391
1403636964451666432 8.511795044 -2.092833042 8.061015129 -0.004633448 0.007672862 -0.052367069 0.998587668
1403636964501666560 8.479001045 -2.094993591 8.045673370 -0.004141486 0.007402187 -0.054261018 0.998490751
1403636964551666432 8.452124596 -2.089994907 8.030582428 -0.004772853 0.005583343 -0.056769978 0.998360276
1403636964601666560 8.417881966 -2.084459782 8.025626183 -0.002974804 0.003522761 -0.063523673 0.997969687
1403636964651666432 8.389394760 -2.080678701 8.003574371 -0.003001570 -0.001179211 -0.066681959 0.997769058
1403636964701666560 8.356513023 -2.079181910 7.991672516 -0.003790854 -0.006357112 -0.071517877 0.997411847
1403636964751666432 8.311666489 -2.072069168 7.972114086 -0.003988571 -0.011755784 -0.077217035 0.996936977
1403636964801666560 8.280492783 -2.067317486 7.957197189 -0.003693837 -0.019513898 -0.082877249 0.996361852
1403636964851666432 8.246011734 -2.064736605 7.928580284 -0.003558048 -0.030359939 -0.083968461 0.995999455
1403636964901666560 8.206716537 -2.054693460 7.913063049 -0.000587459 -0.042641267 -0.084611304 0.995501041
1403636964951666432 8.169685364 -2.040812492 7.902873516 0.002379218 -0.054625586 -0.087468743 0.994665563
1403636965001666560 8.125230789 -2.036404133 7.880192757 0.003952364 -0.066891581 -0.089441247 0.993735433
1403636965051666432 8.081390381 -2.030104399 7.864460945 0.004207528 -0.080720291 -0.090751834 0.992587864
1403636965101666560 8.038899422 -2.032116652 7.836275101 0.001123652 -0.091277212 -0.094517067 0.991329253
1403636965151666432 7.997573376 -2.034140587 7.809510231 -0.001229718 -0.101894185 -0.095432706 0.990206420
1403636965201666560 7.950178623 -2.030927420 7.782746792 -0.006248542 -0.109580487 -0.097213723 0.989192903
1403636965251666432 7.910683155 -2.036595106 7.748157501 -0.013746664 -0.116843037 -0.100792482 0.987926900
1403636965301666560 7.858379841 -2.036006689 7.714766502 -0.024122728 -0.120566480 -0.102323070 0.987123013
1403636965351666432 7.812622070 -2.040160656 7.686436653 -0.035893094 -0.124112390 -0.104734458 0.986072302
1403636965401666560 7.763178825 -2.044092178 7.658461571 -0.047631893 -0.126374125 -0.106954552 0.985048950
1403636965451666432 7.718773365 -2.053531647 7.629882336 -0.057166811 -0.128874540 -0.106804185 0.984233797
1403636965501666560 7.673845768 -2.066931963 7.605975151 -0.063329287 -0.131505415 -0.103201777 0.983892858
1403636965551666432 7.626142502 -2.078105450 7.579022408 -0.061293267 -0.133829802 -0.098916858 0.984148443
1403636965601666560 7.576887131 -2.090618134 7.566041946 -0.053301834 -0.136664003 -0.091093250 0.984979153
1403636965651666432 7.525083065 -2.114864588 7.551198959 -0.042745963 -0.139123276 -0.083735004 0.985802174
1403636965701666560 7.482802868 -2.129617691 7.537858963 -0.032316107 -0.142531067 -0.075220421 0.986398697
1403636965751666432 7.438687325 -2.156946898 7.510170937 -0.024975970 -0.144317657 -0.070191152 0.986722767
1403636965801666560 7.398121357 -2.173161983 7.494918346 -0.018518796 -0.144162372 -0.068053901 0.987037420
1403636965851666432 7.343164444 -2.192481279 7.466397285 -0.013642574 -0.141871527 -0.072486900 0.987133205
1403636965901666560 7.316509724 -2.199646473 7.468191147 -0.010516103 -0.140742883 -0.076703981 0.987014353
1403636965951666432 7.266046047 -2.215245008 7.442296982 -0.008642596 -0.137094051 -0.081045188 0.987199187
1403636966001666560 7.214327812 -2.237831831 7.423982143 -0.008254671 -0.134036362 -0.084391266 0.987342000
1403636966051666432 7.167842388 -2.220747471 7.411875725 -0.004462545 -0.131866276 -0.088019341 0.987341881
1403636966101666560 7.093659401 -2.239373684 7.396525383 -0.004528504 -0.128503889 -0.089803465 0.987624228
1403636966151666432 7.060470581 -2.223761320 7.376950264 -0.001725075 -0.127482533 -0.091121383 0.987644732
1403636966201666560 7.025642395 -2.247391224 7.370848656 -0.003142056 -0.128324240 -0.090565234 0.987583399
1403636966251666432 6.986017704 -2.246660471 7.357835770 -0.001532827 -0.127624214 -0.089388914 0.987785041
1403636966301666560 6.987605572 -2.233690262 7.350576401 -0.000326438 -0.129795000 -0.090007052 0.987447143
1403636966351666432 6.876597404 -2.215639114 7.296474934 0.001663548 -0.125127345 -0.086751878 0.988339245
1403636966401666560 6.802383423 -2.236476660 7.291465759 -0.001485685 -0.125758231 -0.079837725 0.988842070
1403636966451666432 6.729431629 -2.225568056 7.273026466 -0.002260243 -0.125452757 -0.068389751 0.989737034
1403636966501666560 6.685953140 -2.226875305 7.237232208 -0.003091342 -0.127595201 -0.059405059 0.990040898
1403636966551666432 6.670537949 -2.216245651 7.216207027 -0.003365913 -0.129896715 -0.053055011 0.990101337
1403636966601666560 6.627781391 -2.210191488 7.198993683 -0.003316065 -0.128588632 -0.053284869 0.990259886
1403636966651666432 6.586402893 -2.206491470 7.181338787 -0.003166703 -0.125749543 -0.058167946 0.990350187
1403636966701666560 6.560307503 -2.183411121 7.164500237 -0.002765633 -0.123022832 -0.064039409 0.990331590
1403636966751666432 6.527455807 -2.170607805 7.150759697 -0.001685738 -0.119945839 -0.069572009 0.990338266
1403636966801666560 6.491451740 -2.160837889 7.143438816 -0.000937962 -0.117886677 -0.071620256 0.990440488
1403636966851666432 6.469408035 -2.139912844 7.112155914 0.000272081 -0.118233092 -0.071001895 0.990444124
1403636966901666560 6.450432777 -2.134239197 7.088124275 -0.000001701 -0.118876807 -0.068940714 0.990512788
1403636966951666432 6.406449318 -2.127406359 7.063043118 -0.000376452 -0.118530221 -0.065697499 0.990774572
1403636967001666560 6.380270004 -2.119565248 7.044834614 0.000349704 -0.118576534 -0.065955549 0.990751922
1403636967051666432 6.342187881 -2.121620655 7.018705368 -0.000164657 -0.116397172 -0.066971287 0.990942240
1403636967101666560 6.309913635 -2.105748653 6.995477676 0.000635480 -0.114789255 -0.070470579 0.990886927
1403636967151666432 6.287878513 -2.090570450 6.968280315 0.000542336 -0.113454714 -0.073769271 0.990800619
1403636967201666560 6.250727654 -2.084463358 6.935953140 0.000513010 -0.112089224 -0.074892968 0.990871727
1403636967251666432 6.233391285 -2.060276270 6.909730911 0.001558221 -0.112299345 -0.074438147 0.990881145
1403636967301666560 6.221342564 -2.056473970 6.894825935 0.000496003 -0.112549327 -0.076147027 0.990724027
1403636967351666432 6.196354866 -2.033049107 6.859339237 0.002505520 -0.111461647 -0.077186339 0.990763485
1403636967401666560 6.160564423 -2.033518314 6.837263107 0.001582653 -0.110166468 -0.078533135 0.990804434
1403636967451666432 6.135116577 -2.016895056 6.806856155 0.002581168 -0.109740458 -0.078996040 0.990812778
1403636967501666560 6.133587837 -2.009414434 6.761747360 0.003042313 -0.111472659 -0.077990957 0.990697742
1403636967551666432 6.094757080 -2.010679483 6.735281467 0.002354550 -0.109715275 -0.078777663 0.990833521
1403636967601666560 6.083609581 -1.988932133 6.710992813 0.003706352 -0.109624520 -0.079721756 0.990763962
1403636967651666432 6.055900574 -1.993035078 6.671411991 0.003044016 -0.109311692 -0.080080278 0.990771830
1403636967701666560 6.019408226 -1.979693770 6.636764526 0.003136381 -0.107342742 -0.081317104 0.990886092
1403636967751666432 5.983342171 -1.965591908 6.601627350 0.003080878 -0.106145069 -0.080135003 0.991111517
1403636967801666560 5.970604420 -1.948313355 6.568167210 0.003289498 -0.107282206 -0.080242753 0.990979731
1403636967851666432 5.940443039 -1.926750422 6.543702126 0.003126256 -0.106653698 -0.079825647 0.991081774
1403636967901666560 5.907469749 -1.900052667 6.504390240 0.003935127 -0.105867997 -0.079850912 0.991161108
1403636967951666432 5.878166199 -1.872672796 6.479780674 0.004539568 -0.105363660 -0.080588102 0.991152585
1403636968001666560 5.870446205 -1.841629624 6.445731163 0.004549510 -0.106679641 -0.080194108 0.991043746
1403636968051666432 5.833826065 -1.801426888 6.412271976 0.005161248 -0.106131807 -0.079125620 0.991185427
1403636968101666560 5.829918861 -1.769652724 6.376650333 0.006482359 -0.108862191 -0.078015529 0.990969479
1403636968151666432 5.795049667 -1.746085882 6.347018242 0.004690826 -0.108763114 -0.076466911 0.991111219
1403636968201666560 5.776002884 -1.697389364 6.311617851 0.005553101 -0.109335266 -0.075662032 0.991105556
1403636968251666432 5.748114586 -1.683851957 6.269690990 0.003498381 -0.108850986 -0.077215008 0.991048455
1403636968301666560 5.728562355 -1.652153611 6.239468575 0.003142096 -0.109529287 -0.075553447 0.991102993
1403636968351666432 5.683202744 -1.628635168 6.194156647 0.001642913 -0.107599683 -0.076398239 0.991253197
1403636968401666560 5.656169415 -1.610176325 6.151599407 0.000288059 -0.107227206 -0.076498494 0.991287172
1403636968451666432 5.637271404 -1.585055828 6.108167648 -0.000147079 -0.107888147 -0.075604416 0.991284072
1403636968501666560 5.619559288 -1.558822393 6.067185879 -0.000471569 -0.107912287 -0.074912176 0.991333902
1403636968551666432 5.592142105 -1.541134477 6.026114464 -0.000407794 -0.107445441 -0.074969120 0.991380334
1403636968601666560 5.577029228 -1.518560648 5.981743813 0.000392858 -0.107007056 -0.077365771 0.991243601
1403636968651666432 5.546900749 -1.491281986 5.962370396 0.001857332 -0.104329467 -0.081720367 0.991177917
1403636968701666560 5.535358906 -1.488369823 5.889911175 0.000908756 -0.104748942 -0.083207808 0.991011262
1403636968751666432 5.517510414 -1.471570611 5.825556755 0.001011297 -0.104200870 -0.086774729 0.990763009
1403636968801666560 5.495473385 -1.458050370 5.798391342 0.000549965 -0.103416145 -0.087888606 0.990747392
1403636968851666432 5.472644806 -1.444136500 5.709003925 0.000201852 -0.103405461 -0.088344365 0.990708113
1403636968901666560 5.443539619 -1.426098824 5.658575058 -0.000345170 -0.103948854 -0.084702104 0.990969241
1403636968951666432 5.423608780 -1.411311984 5.608660221 -0.000873673 -0.104462549 -0.082998902 0.991059005
1403636969001666560 5.395525455 -1.381792665 5.589447021 0.000114423 -0.104360409 -0.082192644 0.991137326
1403636969051666432 5.372249603 -1.372539282 5.533842564 0.000395254 -0.105163075 -0.079619773 0.991262436
1403636969101666560 5.346967220 -1.360417962 5.481091022 -0.001423479 -0.106128395 -0.076472983 0.991406381
1403636969151666432 5.325215340 -1.362360358 5.398892879 -0.006155054 -0.106755137 -0.074532717 0.991468787
1403636969201666560 5.300959110 -1.336219192 5.375848293 -0.009150431 -0.106220089 -0.075239442 0.991449714
1403636969251666432 5.276881695 -1.328633547 5.316205978 -0.015183142 -0.106329150 -0.073675074 0.991481543
1403636969301666560 5.253520012 -1.323003411 5.255215168 -0.020643270 -0.105708994 -0.074472725 0.991389573
1403636969351666432 5.230319023 -1.319291830 5.200433731 -0.025006175 -0.105198875 -0.075253375 0.991284430
1403636969401666560 5.208328724 -1.316302776 5.149200439 -0.028317060 -0.104252443 -0.076198049 0.991223216
1403636969451666432 5.179551601 -1.313918710 5.087000847 -0.030776339 -0.103158072 -0.077761903 0.991142929
1403636969501666560 5.158992290 -1.306632042 5.034523964 -0.032356817 -0.102549285 -0.078029834 0.991134703
1403636969551666432 5.135391712 -1.302909493 4.984263420 -0.033730771 -0.101873063 -0.078611113 0.991112709
1403636969601666560 5.111750126 -1.295713902 4.934613705 -0.034723349 -0.101293467 -0.077720217 0.991208076
1403636969651666432 5.089593410 -1.289708138 4.884473801 -0.034455772 -0.101170860 -0.077641211 0.991236150
1403636969701666560 5.063625813 -1.280702233 4.836706161 -0.034306552 -0.100602739 -0.077904783 0.991278470
1403636969751666432 5.037517071 -1.270712733 4.788465500 -0.033578921 -0.100323513 -0.077480391 0.991364956
1403636969801666560 5.015433788 -1.261155248 4.743857861 -0.034300856 -0.099930078 -0.078034006 0.991336524
1403636969851666432 4.990012169 -1.251477599 4.702441692 -0.035251096 -0.099540785 -0.077858530 0.991356134
1403636969901666560 4.967999458 -1.237692237 4.660664082 -0.034772739 -0.100173250 -0.076748669 0.991395950
1403636969951666432 4.936769485 -1.224891186 4.619431019 -0.033310313 -0.099417739 -0.077752598 0.991443932
1403636970001666560 4.914373398 -1.210423827 4.581331730 -0.030280238 -0.100601092 -0.075243406 0.991615295
1403636970051666432 4.892521858 -1.194567442 4.542331219 -0.024091847 -0.101373591 -0.074329302 0.991775274
1403636970101666560 4.865136623 -1.179011226 4.506489277 -0.019637754 -0.101637609 -0.075015999 0.991794705
1403636970151666432 4.840325356 -1.162675261 4.470301151 -0.014483151 -0.101942413 -0.075482138 0.991816700
1403636970201666560 4.815830231 -1.145818353 4.434026241 -0.011484364 -0.102413140 -0.074623622 0.991872489
1403636970251666432 4.790823460 -1.129558563 4.396470547 -0.007676018 -0.102876104 -0.075056367 0.991828680
1403636970301666560 4.767764091 -1.114515781 4.359675407 -0.009530070 -0.103726476 -0.074940503 0.991732776
1403636970351666432 4.739593029 -1.095219493 4.326680660 -0.011571052 -0.103258044 -0.074051671 0.991826713
1403636970401666560 4.714022160 -1.078789949 4.288160801 -0.016917583 -0.102652632 -0.075424254 0.991709352
1403636970451666432 4.690510750 -1.062582493 4.250296116 -0.022380155 -0.103100143 -0.076088935 0.991503894
1403636970501666560 4.663031578 -1.048241854 4.216109753 -0.027012298 -0.102848127 -0.075980052 0.991423011
1403636970551666432 4.638440132 -1.034278512 4.175965786 -0.031796739 -0.103100725 -0.076575227 0.991209090
1403636970601666560 4.610912323 -1.020618677 4.138758659 -0.035656795 -0.103009023 -0.076426297 0.991098762
1403636970651666432 4.587217331 -1.010012627 4.103997231 -0.039155573 -0.103734836 -0.078315504 0.990743458
1403636970701666560 4.561161041 -1.000630021 4.068643570 -0.042851724 -0.103866696 -0.079167373 0.990508914
1403636970751666432 4.531336784 -0.995746970 4.034692764 -0.046856511 -0.103962518 -0.079195864 0.990315259
1403636970801666560 4.503896713 -0.989997864 4.002227306 -0.049994040 -0.104044572 -0.080524988 0.990045965
1403636970851666432 4.476319313 -0.985270023 3.970431089 -0.055312809 -0.104347833 -0.082023434 0.989608109
1403636970901666560 4.451545715 -0.975710988 3.939723969 -0.058818862 -0.104871012 -0.081292890 0.989410877
1403636970951666432 4.415698528 -0.968272924 3.917129993 -0.061958097 -0.104652792 -0.080260664 0.989326656
1403636971001666560 4.388501167 -0.965881467 3.893414021 -0.063226931 -0.106236547 -0.077217840 0.989319742
1403636971051666432 4.359842777 -0.954867303 3.870062351 -0.060636975 -0.107906446 -0.071896710 0.989702106
1403636971101666560 4.329795837 -0.951135993 3.854371786 -0.057567537 -0.110346869 -0.065590307 0.990054250
1403636971151666432 4.302371979 -0.946385741 3.838559866 -0.053002160 -0.113084458 -0.060403433 0.990330279
1403636971201666560 4.270258427 -0.939815760 3.826487780 -0.048725843 -0.114975356 -0.052452102 0.990785182
1403636971251666432 4.242312908 -0.926177263 3.814832926 -0.043323722 -0.117408916 -0.045720339 0.991084158
1403636971301666560 4.213297844 -0.920010149 3.803973675 -0.039827712 -0.119288526 -0.039240897 0.991284132
1403636971351666432 4.187551498 -0.910102010 3.795593262 -0.037622992 -0.120973878 -0.034165062 0.991353929
1403636971401666560 4.165486336 -0.894290090 3.788507938 -0.034976408 -0.122315817 -0.030410664 0.991408408
1403636971451666432 4.150232315 -0.880442739 3.779290199 -0.033245038 -0.122934587 -0.030172687 0.991398752
1403636971501666560 4.132877827 -0.866232276 3.774980545 -0.032866463 -0.121912338 -0.033430409 0.991433084
1403636971551666432 4.113529205 -0.854138732 3.776352406 -0.032031648 -0.121023320 -0.036569972 0.991458476
1403636971601666560 4.102590561 -0.839344144 3.770312786 -0.028236188 -0.119812697 -0.043141197 0.991456747
1403636971651666432 4.091122150 -0.824018002 3.770554781 -0.023136903 -0.118257888 -0.048998583 0.991503358
1403636971701666560 4.078433037 -0.803657472 3.770837307 -0.017867019 -0.116372973 -0.056086283 0.991459727
1403636971751666432 4.071341991 -0.789487362 3.771839142 -0.014116526 -0.116418369 -0.059413068 0.991321146
1403636971801666560 4.059609413 -0.776235938 3.770014524 -0.011129963 -0.116460204 -0.060174208 0.991308331
1403636971851666432 4.053337097 -0.756851614 3.767121315 -0.007884476 -0.117414705 -0.059968889 0.991239309
1403636971901666560 4.043401718 -0.737332880 3.772738457 -0.006756448 -0.117231257 -0.061175860 0.991195560
1403636971951666432 4.031287193 -0.721562386 3.769772530 -0.006781344 -0.117057256 -0.061789755 0.991177917
1403636972001666560 4.030235291 -0.708317935 3.762834072 -0.006746430 -0.117941104 -0.061550908 0.991088212
1403636972051666432 4.025192261 -0.692192793 3.757943630 -0.004998057 -0.117834941 -0.061048087 0.991142333
1403636972101666560 4.021562099 -0.686207235 3.748737335 -0.006060148 -0.117491677 -0.062500075 0.991086662
1403636972151666432 4.011038780 -0.678004682 3.749164104 -0.008431830 -0.116930708 -0.063473411 0.991073787
1403636972201666560 4.005434990 -0.668587327 3.741837502 -0.012114642 -0.117264979 -0.060215551 0.991199374
1403636972251666432 4.002284527 -0.665364742 3.732921124 -0.017190721 -0.117785119 -0.057637937 0.991215944
1403636972301666560 3.998475552 -0.662594795 3.724495411 -0.022628566 -0.117960960 -0.058549732 0.991032362
1403636972351666432 3.998895407 -0.659056723 3.713974714 -0.024599170 -0.117424063 -0.059316050 0.991003573
1403636972401666560 3.997695208 -0.658676803 3.706003904 -0.026093584 -0.116964243 -0.060066871 0.990974486
1403636972451666432 3.995607376 -0.659768164 3.701318264 -0.025961433 -0.115730040 -0.062430199 0.990976810
1403636972501666560 3.991745949 -0.663532436 3.694171429 -0.023905899 -0.114629239 -0.063548669 0.991085410
1403636972551666432 3.990766525 -0.671742737 3.684106350 -0.022707837 -0.114018865 -0.065339200 0.991067529
1403636972601666560 3.995451212 -0.679826081 3.673056364 -0.020959586 -0.113641351 -0.066161625 0.991094828
1403636972651666432 3.997054100 -0.690799892 3.667711735 -0.018358782 -0.112571105 -0.069286257 0.991055071
1403636972701666560 3.996126652 -0.698994040 3.656224251 -0.017814238 -0.111779690 -0.069592997 0.991133094
1403636972751666432 3.997034073 -0.704855204 3.646941662 -0.017510815 -0.111281671 -0.070101246 0.991158724
1403636972801666560 3.997664928 -0.709293306 3.638050318 -0.017497715 -0.111140750 -0.070185281 0.991168797
1403636972851666432 3.998488426 -0.714445770 3.632401466 -0.018322969 -0.110799238 -0.070651740 0.991158962
1403636972901666560 3.999472618 -0.717673421 3.626507759 -0.018622257 -0.109700762 -0.071236379 0.991233766
1403636972951666432 4.000224113 -0.709353924 3.624832153 -0.018724842 -0.106962644 -0.068820536 0.991701603
1403636973001666560 4.000757694 -0.713457823 3.617877483 -0.021782961 -0.101699799 -0.069185831 0.992167294
1403636973051666432 4.005257130 -0.707131922 3.610550880 -0.023880806 -0.096409164 -0.066828720 0.992808580
1403636973101666560 4.009619236 -0.709529579 3.611188412 -0.024971431 -0.090833366 -0.063857034 0.993502915
1403636973151666432 4.007668495 -0.687562346 3.608097553 -0.024437618 -0.084828414 -0.063040271 0.994099021
1403636973201666560 4.011706829 -0.686362982 3.603098631 -0.026266003 -0.080733255 -0.062001348 0.994458675
1403636973251666432 4.014104366 -0.670419931 3.604113817 -0.023638064 -0.076116815 -0.060036473 0.995009124
1403636973301666560 4.018486023 -0.664939046 3.601652622 -0.023831567 -0.072759420 -0.059937701 0.995261550
1403636973351666432 4.019150257 -0.656628072 3.599917889 -0.023774888 -0.069610506 -0.058974918 0.995545626
1403636973401666560 4.022397995 -0.643280387 3.599877357 -0.022873588 -0.066493720 -0.058600347 0.995801866
1403636973451666432 4.022951126 -0.635973334 3.601670265 -0.024356417 -0.064594075 -0.057678226 0.995945573
1403636973501666560 4.027252674 -0.622027755 3.600210905 -0.023479296 -0.062579721 -0.057402216 0.996111155
1403636973551666432 4.028320789 -0.610060334 3.602331638 -0.022523385 -0.060503770 -0.059129026 0.996160507
1403636973601666560 4.028697968 -0.595804513 3.609313726 -0.020073410 -0.059242129 -0.058558349 0.996322393
1403636973651666432 4.029242516 -0.590996265 3.608890295 -0.018614503 -0.058164436 -0.058171447 0.996436894
1403636973701666560 4.030478954 -0.580656707 3.613646507 -0.017937390 -0.057637908 -0.058895547 0.996437371
1403636973751666432 4.030478001 -0.557232559 3.613850355 -0.013832008 -0.056469563 -0.059531223 0.996531904
1403636973801666560 4.028324604 -0.552971601 3.617098331 -0.012189894 -0.056002863 -0.059985764 0.996552467
1403636973851666432 4.031885624 -0.543786466 3.615294933 -0.010886006 -0.056354567 -0.060768541 0.996500313
1403636973901666560 4.034479141 -0.537812412 3.611730099 -0.010396878 -0.056946345 -0.059999555 0.996518493
1403636973951666432 4.036116600 -0.530234694 3.610433102 -0.009707345 -0.057977539 -0.058258526 0.996569276
1403636974001666560 4.034386635 -0.526729822 3.607960224 -0.012359426 -0.057504058 -0.056951590 0.996642888
1403636974051666432 4.028222084 -0.523396194 3.609965801 -0.014698021 -0.054971382 -0.054220486 0.996906340
1403636974101666560 4.030232430 -0.523028374 3.604575157 -0.017468639 -0.051281981 -0.051340789 0.997210681
1403636974151666432 4.031672955 -0.522306204 3.600148201 -0.021150978 -0.044887811 -0.047619808 0.997632205
1403636974201666560 4.031276703 -0.517205179 3.596733332 -0.021845520 -0.035547175 -0.044258643 0.998148441
1403636974251666432 4.033824444 -0.513121665 3.599009991 -0.021961916 -0.024393272 -0.042742372 0.998546779
1403636974301666560 4.037987709 -0.505008638 3.594666481 -0.022130964 -0.011642328 -0.039983019 0.998887420
1403636974351666432 4.035602570 -0.499268293 3.596646309 -0.020891132 0.002680212 -0.038170815 0.999049246
1403636974401666560 4.041528702 -0.488519311 3.594330549 -0.019903809 0.016092371 -0.033614971 0.999107063
1403636974451666432 4.044669151 -0.484554410 3.596025467 -0.017964734 0.031072685 -0.029594876 0.998917341
1403636974501666560 4.047008514 -0.474676907 3.599885464 -0.016383721 0.045773301 -0.024608964 0.998514295
1403636974551666432 4.052484989 -0.468177974 3.598011255 -0.015403214 0.060282178 -0.020710994 0.997847617
1403636974601666560 4.049942017 -0.451168835 3.603708267 -0.012218787 0.076958023 -0.015822358 0.996833920
1403636974651666432 4.056456089 -0.439954609 3.604459286 -0.013002170 0.091662936 -0.011956592 0.995633423
1403636974701666560 4.054307461 -0.426516980 3.606130838 -0.013667646 0.106176183 -0.005381364 0.994238853
1403636974751666432 4.056686878 -0.411898971 3.602822304 -0.014767190 0.119575866 0.001547220 0.992714047
1403636974801666560 4.057655334 -0.405941129 3.607352972 -0.018286450 0.132286191 0.007978766 0.991010725
1403636974851666432 4.059122086 -0.398179144 3.607420206 -0.020496504 0.143030167 0.016820794 0.989363074
1403636974901666560 4.057486057 -0.396339566 3.602592945 -0.024486193 0.153784171 0.025323056 0.987476349
1403636974951666432 4.058646202 -0.394644290 3.605302811 -0.026658364 0.164343223 0.033115283 0.985486686
1403636975001666560 4.061046600 -0.396428764 3.607021809 -0.029612405 0.174311429 0.039478865 0.983453095
1403636975051666432 4.061062813 -0.398705870 3.602535248 -0.029536976 0.184730053 0.044840846 0.981321394
1403636975101666560 4.063560963 -0.401363403 3.606989145 -0.027955649 0.195435807 0.045543842 0.979259431
1403636975151666432 4.068933010 -0.408899516 3.608511209 -0.025452126 0.204277217 0.045562133 0.977520883
1403636975201666560 4.075206757 -0.404344857 3.605134249 -0.020230589 0.211992890 0.044750348 0.976036489
1403636975251666432 4.082694054 -0.407069325 3.603759527 -0.016330563 0.218611300 0.042336572 0.974756420
1403636975301666560 4.087053776 -0.404602587 3.603639126 -0.012274502 0.223513171 0.040970739 0.973762095
1403636975351666432 4.091894150 -0.404859126 3.606672525 -0.008430031 0.227082834 0.039683841 0.973030031
1403636975401666560 4.095515251 -0.401678145 3.609026909 -0.008310728 0.230060458 0.037496183 0.972418189
1403636975451666432 4.099411488 -0.399981469 3.610599041 -0.008835290 0.231566042 0.037177078 0.972068429
1403636975501666560 4.104364872 -0.389858723 3.617816448 -0.010583258 0.232386976 0.036893580 0.971865833
1403636975551666432 4.110399246 -0.384001970 3.620358706 -0.013807512 0.232457921 0.037315421 0.971792281
1403636975601666560 4.111605644 -0.376774549 3.620993137 -0.017093396 0.232584089 0.036863450 0.971727073
1403636975651666432 4.111569881 -0.375963628 3.631582499 -0.020159490 0.232144177 0.036248937 0.971796632
1403636975701666560 4.112318993 -0.374801546 3.626868248 -0.022322981 0.231174216 0.035973601 0.971990764
1403636975751666432 4.119339943 -0.379766613 3.629415989 -0.025002267 0.229241759 0.035366394 0.972405434
1403636975801666560 4.121519566 -0.389934242 3.630599737 -0.026889265 0.228344128 0.035149664 0.972574115
1403636975851666432 4.124918938 -0.385012150 3.632354259 -0.026690440 0.229617491 0.036365572 0.972235024
1403636975901666560 4.126742840 -0.396513939 3.635101795 -0.028914126 0.233074248 0.036926661 0.971327305
1403636975951666432 4.127249718 -0.401656121 3.641735554 -0.028374992 0.238129467 0.039887786 0.969999075
1403636976001666560 4.135391712 -0.408396572 3.646915674 -0.026320115 0.243644774 0.044133969 0.968502283
1403636976051666432 4.133466244 -0.408912331 3.653588295 -0.020908501 0.251397580 0.049345069 0.966399074
1403636976101666560 4.142068863 -0.414138705 3.657496452 -0.014448780 0.258380949 0.057817508 0.964203119
1403636976151666432 4.148469925 -0.417505890 3.669154406 -0.007933703 0.266125679 0.066604108 0.961601794
1403636976201666560 4.154640675 -0.417545617 3.676885605 -0.002162724 0.274801016 0.076049782 0.958486378
1403636976251666432 4.163836956 -0.418117404 3.678200722 0.002589106 0.283804566 0.085947111 0.955018997
1403636976301666560 4.174681664 -0.413487852 3.681389332 0.005340681 0.294466883 0.092925027 0.951118112
1403636976351666432 4.180075169 -0.414686352 3.688762665 0.007651141 0.306748509 0.099150531 0.946581244
1403636976401666560 4.185908794 -0.412659019 3.694148064 0.008110145 0.319729000 0.103396043 0.941815734
1403636976451666432 4.193928719 -0.404308617 3.697748661 0.009263260 0.333117962 0.106827088 0.936768174
1403636976501666560 4.209711552 -0.401317477 3.698830843 0.006473544 0.346459508 0.107106268 0.931907773
1403636976551666432 4.228486061 -0.386733294 3.695978642 0.004109600 0.358606964 0.104636736 0.927596569
1403636976601666560 4.242331505 -0.379442722 3.700581789 0.000985064 0.369819939 0.101267301 0.923567593
1403636976651666432 4.254489422 -0.363224000 3.702692032 -0.001072554 0.378891796 0.098400943 0.920194030
1403636976701666560 4.265634060 -0.355085731 3.696896315 -0.002821166 0.386026382 0.096509747 0.917421162
1403636976751666432 4.274177551 -0.341959178 3.709561348 -0.004252582 0.392535508 0.096117638 0.914690733
1403636976801666560 4.291038513 -0.321954429 3.699803114 -0.005704173 0.395498663 0.098494194 0.913152277
1403636976851666432 4.301574707 -0.297500253 3.709447384 -0.009297367 0.398136288 0.101907715 0.911600709
1403636976901666560 4.313491344 -0.289623857 3.709149122 -0.012368679 0.399476022 0.105447516 0.910574973
1403636976951666432 4.327770233 -0.272253871 3.706796885 -0.014047664 0.399592608 0.110085383 0.909950316
1403636977001666560 4.338524342 -0.261407793 3.713733196 -0.014240303 0.400368512 0.112020589 0.909369946
1403636977051666432 4.352083683 -0.251376390 3.712922573 -0.016074957 0.400027066 0.113364086 0.909323096
1403636977101666560 4.363163948 -0.242672920 3.709983110 -0.016203696 0.399532616 0.114725932 0.909367442
1403636977151666432 4.371664047 -0.236999333 3.715995789 -0.016787825 0.399557054 0.115207672 0.909285188
1403636977201666560 4.390797138 -0.237403214 3.709798336 -0.017888119 0.397640944 0.116351262 0.909958303
1403636977251666432 4.407481194 -0.231819332 3.710476398 -0.017831808 0.396447241 0.116485901 0.910462856
1403636977301666560 4.422286034 -0.236296952 3.704039574 -0.018421970 0.395352006 0.115534022 0.911048472
1403636977351666432 4.441148281 -0.236009419 3.702740192 -0.015572994 0.394246876 0.114594266 0.911698997
1403636977401666560 4.463325977 -0.223002732 3.695802212 -0.012394130 0.392878801 0.111711323 0.912695587
1403636977451666432 4.479192734 -0.222526312 3.701477051 -0.009323401 0.393142313 0.107333228 0.913143873
1403636977501666560 4.500103951 -0.211776018 3.694868088 -0.006259597 0.392055184 0.104361862 0.913981497
1403636977551666432 4.517780304 -0.212742001 3.706283331 -0.004104908 0.392714262 0.100378290 0.914156914
1403636977601666560 4.541980743 -0.198823869 3.705414534 -0.001249052 0.391414106 0.099897183 0.914775372
1403636977651666432 4.562271595 -0.192262888 3.699029922 0.000030763 0.390904725 0.098225601 0.915174961
1403636977701666560 4.574004650 -0.193622261 3.693202734 -0.000969403 0.391162336 0.098871961 0.914994776
1403636977751666432 4.608035564 -0.178196013 3.690599442 -0.001118794 0.391133696 0.103034899 0.914547443
1403636977801666560 4.624245167 -0.160692215 3.693570375 -0.000772782 0.391958177 0.107882693 0.913635314
1403636977851666432 4.648061752 -0.150044322 3.688750267 -0.002368492 0.392056942 0.113030843 0.912967563
1403636977901666560 4.675632000 -0.130648494 3.688734055 -0.001972758 0.392855972 0.114139505 0.912486970
1403636977951666432 4.686610222 -0.118654370 3.687991381 -0.000891990 0.395750374 0.112804405 0.911403298
1403636978001666560 4.712416172 -0.110661149 3.687921047 -0.000669787 0.397743374 0.111193776 0.910733640
1403636978051666432 4.727668762 -0.102915585 3.680004120 -0.001032630 0.400303662 0.108102091 0.909983456
1403636978101666560 4.756947517 -0.093424916 3.670429707 -0.002080095 0.401758403 0.106270604 0.909556150
1403636978151666432 4.779171467 -0.086370826 3.671171188 -0.003152478 0.403339922 0.105757192 0.908912778
1403636978201666560 4.801899433 -0.079311609 3.662574291 -0.005542020 0.404784381 0.103877164 0.908475876
1403636978251666432 4.819304466 -0.074339688 3.656679392 -0.007740080 0.405949742 0.103868797 0.907940626
1403636978301666560 4.844465256 -0.080985665 3.642918825 -0.010370357 0.406496793 0.103334777 0.907730520
1403636978351666432 4.863222122 -0.077678502 3.635487795 -0.012618658 0.407258034 0.103998005 0.907285035
1403636978401666560 4.886766434 -0.080717623 3.627725124 -0.016091110 0.407519609 0.103755921 0.907140315
1403636978451666432 4.904748440 -0.083710194 3.617918730 -0.021132171 0.408249229 0.103621453 0.906724095
1403636978501666560 4.925292015 -0.092691123 3.604721546 -0.026762929 0.408106387 0.105773784 0.906391084
1403636978551666432 4.945106506 -0.107885599 3.603352070 -0.033099554 0.408949643 0.106928945 0.905665994
1403636978601666560 4.966417789 -0.097971976 3.592962503 -0.036338512 0.408611029 0.109705985 0.905362427
1403636978651666432 4.989836693 -0.094099462 3.582620859 -0.039218999 0.408534825 0.111096561 0.905107021
1403636978701666560 5.012244225 -0.098281145 3.581916094 -0.042317189 0.408861607 0.111392081 0.904783547
1403636978751666432 5.035287380 -0.104212642 3.583991528 -0.045339108 0.409156650 0.111615673 0.904476166
1403636978801666560 5.063333988 -0.097563744 3.577928543 -0.046066217 0.408957064 0.113009617 0.904356599
1403636978851666432 5.093801498 -0.096448898 3.580250263 -0.044545162 0.408939242 0.112110220 0.904552758
1403636978901666560 5.115650177 -0.096966028 3.579123497 -0.040697634 0.409558922 0.110514738 0.904650033
1403636978951666432 5.147210121 -0.098716021 3.584008455 -0.035756391 0.410326511 0.107799597 0.904838622
1403636979001666560 5.174047470 -0.094453692 3.591627359 -0.027642844 0.412281752 0.104272194 0.904647410
1403636979051666432 5.202116013 -0.089691877 3.601107836 -0.020098619 0.413285196 0.100273401 0.904840648
1403636979101666560 5.231580734 -0.085283339 3.608517885 -0.014385447 0.413956672 0.097360373 0.904960692
1403636979151666432 5.266363144 -0.073195696 3.610445261 -0.009305164 0.413666666 0.096206300 0.905283213
1403636979201666560 5.287550926 -0.070864916 3.620496273 -0.009525588 0.414171934 0.095853649 0.905087292
1403636979251666432 5.312811852 -0.055399835 3.635233402 -0.012799954 0.413852811 0.097070284 0.905063212
1403636979301666560 5.344038010 -0.047821403 3.642399549 -0.017859053 0.413051605 0.099086873 0.905124903
1403636979351666432 5.366633892 -0.032582462 3.655129910 -0.022255350 0.412990808 0.100661002 0.904881597
1403636979401666560 5.396949291 -0.032135308 3.665743828 -0.028333437 0.412312597 0.101589017 0.904917240
1403636979451666432 5.425220013 -0.026870728 3.671895027 -0.032071102 0.411469251 0.104362644 0.904860735
1403636979501666560 5.451455593 -0.032036424 3.679122448 -0.035306424 0.410355449 0.106680475 0.904975772
1403636979551666432 5.477718353 -0.032355666 3.695199251 -0.038089272 0.410923511 0.107357733 0.904524982
1403636979601666560 5.504841805 -0.033868790 3.703970909 -0.038736776 0.410482019 0.107841864 0.904640317
1403636979651666432 5.531620979 -0.042744994 3.714224815 -0.039607290 0.410861909 0.109322757 0.904252350
1403636979701666560 5.559964180 -0.049483299 3.728688240 -0.041378587 0.412483573 0.107510515 0.903651774
1403636979751666432 5.588790894 -0.058602095 3.742258787 -0.042319838 0.412932396 0.108000644 0.903344750
1403636979801666560 5.622769356 -0.070670962 3.753880978 -0.039898563 0.413683295 0.107000098 0.903230429
1403636979851666432 5.651610374 -0.082574368 3.771231174 -0.035501957 0.415794313 0.104212716 0.902770400
1403636979901666560 5.686766148 -0.097924769 3.788978338 -0.031467840 0.416716397 0.103841133 0.902537644
1403636979951666432 5.715049267 -0.103540361 3.802549839 -0.026882216 0.418532759 0.102127068 0.902040839
1403636980001666560 5.746640205 -0.114046991 3.820472717 -0.025330290 0.419962496 0.100598127 0.901592970
1403636980051666432 5.777661324 -0.129008055 3.845951319 -0.024468448 0.421575606 0.099363923 0.901000619
1403636980101666560 5.809267521 -0.133282125 3.859336853 -0.022751451 0.421914518 0.099505655 0.900871336
1403636980151666432 5.839972019 -0.145852923 3.886326790 -0.021794481 0.422883511 0.099148735 0.900479913
1403636980201666560 5.869452477 -0.148992717 3.906785250 -0.021104617 0.423702508 0.099678032 0.900052786
1403636980251666432 5.901447773 -0.153780222 3.932369232 -0.020178841 0.423919886 0.100305058 0.899902046
1403636980301666560 5.934368134 -0.157990634 3.952736616 -0.016545331 0.424074471 0.101423278 0.899778008
1403636980351666432 5.965707779 -0.160738885 3.979269743 -0.013475315 0.424493551 0.100536637 0.899731040
1403636980401666560 5.995676994 -0.160816729 4.005016327 -0.008727997 0.424221575 0.101035804 0.899861991
1403636980451666432 6.023089409 -0.158219635 4.026196003 -0.005282377 0.424347252 0.100490756 0.899890602
1403636980501666560 6.053369045 -0.159097195 4.052959919 -0.001935364 0.423705339 0.102352880 0.899996638
1403636980551666432 6.077597141 -0.160721123 4.083039284 -0.000032585 0.423071980 0.103726782 0.900139332
1403636980601666560 6.106568336 -0.155171633 4.106454849 0.003072143 0.421817780 0.105606526 0.900504112
1403636980651666432 6.134306908 -0.157721221 4.135884285 0.004489402 0.420771033 0.106648982 0.900864899
1403636980701666560 6.161450863 -0.155025840 4.153951168 0.004724486 0.420398384 0.105786867 0.901139259
1403636980751666432 6.182347298 -0.154022396 4.179846764 0.003028269 0.420546412 0.105401464 0.901122689
1403636980801666560 6.209803581 -0.157120526 4.201779842 -0.001508779 0.421045095 0.102451794 0.901233852
1403636980851666432 6.235013962 -0.156670570 4.222356796 -0.006274484 0.420135945 0.101268880 0.901771069
1403636980901666560 6.260189056 -0.161861479 4.238282204 -0.010624066 0.419957936 0.100522958 0.901896656
1403636980951666432 6.284510136 -0.168517888 4.259675980 -0.014008012 0.420151591 0.098847724 0.901945412
1403636981001666560 6.305742264 -0.176068544 4.274817944 -0.016237807 0.419772893 0.098519482 0.902120233
1403636981051666432 6.325819969 -0.180648506 4.290822983 -0.016776185 0.419404298 0.097529233 0.902389407
1403636981101666560 6.344667435 -0.187215388 4.311592102 -0.014535696 0.419357985 0.098644100 0.902328610
1403636981151666432 6.366176605 -0.190255165 4.336663246 -0.012076419 0.418627948 0.100788638 0.902466834
1403636981201666560 6.387140274 -0.195861220 4.352115631 -0.008776786 0.417609096 0.105860986 0.902396262
1403636981251666432 6.408097267 -0.199384749 4.369197845 -0.004204986 0.416023880 0.111495994 0.902482748
1403636981301666560 6.430795193 -0.203251004 4.391505718 0.001496389 0.414501607 0.117453344 0.902436078
1403636981351666432 6.453469753 -0.200590849 4.425312996 0.006187925 0.413740247 0.121387042 0.902244925
1403636981401666560 6.474771023 -0.200648129 4.444707394 0.007685608 0.413632929 0.123959117 0.901932895
1403636981451666432 6.495657921 -0.199555933 4.466351509 0.005851180 0.415481418 0.121899173 0.901377559
1403636981501666560 6.518039703 -0.194398999 4.484779835 0.002429074 0.417893142 0.118733972 0.900700629
1403636981551666432 6.539819241 -0.189105868 4.502660751 -0.002699586 0.420841634 0.113257274 0.900032103
1403636981601666560 6.561376095 -0.185425222 4.520378590 -0.009310190 0.423794389 0.108407363 0.899199367
1403636981651666432 6.583144665 -0.186734438 4.537263870 -0.014500506 0.426347494 0.104249589 0.898415029
1403636981701666560 6.603275776 -0.187192023 4.552335739 -0.017862111 0.428283155 0.102706574 0.897611201
1403636981751666432 6.624547482 -0.192660332 4.569871426 -0.021285832 0.430001587 0.100779288 0.896933138
1403636981801666560 6.644386292 -0.197511196 4.587313652 -0.024977388 0.431138456 0.101315178 0.896231532
1403636981851666432 6.664463520 -0.206735373 4.598154545 -0.028927952 0.431895763 0.102797329 0.895579100
1403636981901666560 6.683675766 -0.216721058 4.617020130 -0.033301745 0.432576239 0.103712089 0.894993067
1403636981951666432 6.708119392 -0.231127977 4.638095856 -0.038236357 0.432579398 0.107265435 0.894375324
1403636982001666560 6.729290962 -0.238573432 4.655102253 -0.042055562 0.432640105 0.110342436 0.893800020
1403636982051666432 6.745394230 -0.251288056 4.667535782 -0.046068769 0.431786656 0.115123473 0.893411756
1403636982101666560 6.768550873 -0.260747671 4.690661430 -0.049583077 0.431064755 0.118343569 0.893151402
1403636982151666432 6.792685509 -0.270988345 4.711283684 -0.051228210 0.430177182 0.122107834 0.892979801
1403636982201666560 6.817677975 -0.281452894 4.742224693 -0.051387221 0.429690033 0.124787629 0.892834723
1403636982251666432 6.840119362 -0.292799592 4.763344765 -0.049278166 0.428775400 0.128106534 0.892923295
1403636982301666560 6.869657516 -0.299160123 4.792605877 -0.045204472 0.427857310 0.131056935 0.893151045
1403636982351666432 6.899052620 -0.311263323 4.825386524 -0.040497191 0.427474678 0.131576002 0.893483698
1403636982401666560 6.924870491 -0.322087049 4.845280647 -0.033611018 0.427477449 0.131709784 0.893748224
1403636982451666432 6.960337162 -0.328633189 4.876633167 -0.025392089 0.427519321 0.130156547 0.894226909
1403636982501666560 6.994191170 -0.339307547 4.911375523 -0.017276723 0.427420288 0.127417684 0.894862056
1403636982551666432 7.029052258 -0.350615978 4.940744400 -0.011712731 0.427713871 0.124319553 0.895247579
1403636982601666560 7.062542439 -0.363278866 4.972191811 -0.009625665 0.427900851 0.121749595 0.895536304
1403636982651666432 7.097640991 -0.376389384 4.999446869 -0.009526129 0.426568627 0.123245023 0.895968258
1403636982701666560 7.128870964 -0.392675996 5.017796516 -0.009817977 0.425516397 0.123269044 0.896462023
1403636982751666432 7.164770126 -0.407137036 5.043344975 -0.013346856 0.424556673 0.123210132 0.896879494
1403636982801666560 7.199284554 -0.422004223 5.070863247 -0.016011460 0.424144238 0.122073784 0.897186339
1403636982851666432 7.235795021 -0.435936809 5.095323563 -0.019013623 0.423881978 0.121301688 0.897356391
1403636982901666560 7.272011757 -0.448459983 5.115959167 -0.021991204 0.423755407 0.120166734 0.897500813
1403636982951666432 7.310598373 -0.460038900 5.146927834 -0.022163510 0.424216390 0.117900863 0.897579312
1403636983001666560 7.347557545 -0.468076587 5.170842171 -0.021432970 0.424722731 0.116329283 0.897562683
1403636983051666432 7.387962341 -0.479580879 5.204358101 -0.018716732 0.425371826 0.113379687 0.897693455
1403636983101666560 7.425162315 -0.485951304 5.227490902 -0.015416253 0.425811261 0.111792229 0.897746980
1403636983151666432 7.465477467 -0.493997097 5.248667717 -0.013626278 0.426054299 0.109971873 0.897885382
1403636983201666560 7.506619453 -0.498416901 5.283082962 -0.013185373 0.427279860 0.106526479 0.897724986
1403636983251666432 7.542803764 -0.498110175 5.306676865 -0.011980426 0.427845478 0.104664102 0.897691607
1403636983301666560 7.585194111 -0.503506780 5.336576939 -0.012134173 0.428858787 0.102318555 0.897476375
1403636983351666432 7.622664452 -0.507918715 5.370225430 -0.011813762 0.429644942 0.101691045 0.897175908
1403636983401666560 7.663159847 -0.505504310 5.395679951 -0.011297464 0.430137008 0.099595703 0.897181809
1403636983451666432 7.699732304 -0.507657409 5.420773029 -0.010688364 0.430297136 0.100155801 0.897050142
1403636983501666560 7.736354828 -0.507906377 5.449539661 -0.011224800 0.430258185 0.101133555 0.896952569
1403636983551666432 7.774253845 -0.508715272 5.487609386 -0.012861371 0.431492895 0.101358756 0.896311820
1403636983601666560 7.806415081 -0.512292147 5.507988930 -0.015619240 0.431690514 0.101006195 0.896212637
1403636983651666432 7.842533112 -0.518726707 5.537643909 -0.019766236 0.432067215 0.102533311 0.895775676
1403636983701666560 7.877213955 -0.527005076 5.565565586 -0.022375213 0.432732493 0.103860058 0.895240188
1403636983751666432 7.910573959 -0.534014702 5.597254753 -0.025213180 0.433413923 0.104426041 0.894769132
1403636983801666560 7.945355892 -0.546896458 5.625695705 -0.027652293 0.434241742 0.104647741 0.894269705
1403636983851666432 7.978771210 -0.562207222 5.644429207 -0.030553371 0.434229791 0.106041096 0.894016981
1403636983901666560 8.008527756 -0.576097012 5.675455093 -0.032018065 0.434703708 0.106646612 0.893663287
1403636983951666432 8.043203354 -0.595009208 5.703715324 -0.033551551 0.435278982 0.107993998 0.893165052
1403636984001666560 8.077577591 -0.615191102 5.726143360 -0.034541953 0.435344279 0.109179191 0.892951369
1403636984051666432 8.112027168 -0.633504391 5.760630608 -0.035833754 0.435961753 0.110621214 0.892421544
1403636984101666560 8.146571159 -0.660102129 5.792506218 -0.036610875 0.436751634 0.111223482 0.891928792
1403636984151666432 8.180237770 -0.676319242 5.825058937 -0.034955028 0.437586933 0.110423855 0.891685128
1403636984201666560 8.216224670 -0.694684625 5.859808922 -0.032950655 0.438880950 0.108873494 0.891316056
1403636984251666432 8.251355171 -0.711333752 5.893169880 -0.028638441 0.439804822 0.108298838 0.891079605
1403636984301666560 8.288567543 -0.727084994 5.929481030 -0.026117032 0.440939784 0.106263414 0.890841246
1403636984351666432 8.322883606 -0.740453362 5.969497204 -0.023154439 0.442040980 0.106015220 0.890406907
1403636984401666560 8.358549118 -0.750767469 6.005926609 -0.021547329 0.442768723 0.105122536 0.890191495
1403636984451666432 8.392969131 -0.762174726 6.042771816 -0.020087915 0.443589002 0.103683285 0.889985979
1403636984501666560 8.430024147 -0.769871473 6.086164951 -0.018078053 0.444480360 0.102955289 0.889668822
1403636984551666432 8.462916374 -0.777354836 6.121926785 -0.017469076 0.444480151 0.102360345 0.889749706
1403636984601666560 8.495474815 -0.786102533 6.166415215 -0.016907714 0.445034444 0.102139078 0.889508903
1403636984651666432 8.529130936 -0.795017838 6.201278210 -0.016613256 0.444560677 0.102058567 0.889760554
1403636984701666560 8.558959961 -0.806679845 6.243592262 -0.016464774 0.444780439 0.100932032 0.889781952
1403636984751666432 8.589832306 -0.820873499 6.279712677 -0.014854447 0.443921685 0.102140173 0.890101254
1403636984801666560 8.622013092 -0.834507108 6.322976112 -0.013380129 0.443246990 0.103675939 0.890283287
1403636984851666432 8.651116371 -0.849429250 6.360059738 -0.012159410 0.442058027 0.106351376 0.890576363
1403636984901666560 8.681381226 -0.862954617 6.401153088 -0.010534997 0.441167265 0.108841829 0.890737832
1403636984951666432 8.709890366 -0.884042025 6.438379765 -0.009603722 0.440689832 0.109791279 0.890868187
1403636985001666560 8.740618706 -0.903958440 6.476293564 -0.009270107 0.440283924 0.110741928 0.890954733
1403636985051666432 8.768460274 -0.921126723 6.511898518 -0.009512587 0.440156013 0.110678621 0.891023278
1403636985101666560 8.794410706 -0.941399336 6.548522472 -0.010554510 0.441014349 0.109805413 0.890695095
1403636985151666432 8.823364258 -0.951945901 6.588680267 -0.012411262 0.441524684 0.108319029 0.890600264
1403636985201666560 8.849409103 -0.970028996 6.623953819 -0.013030158 0.442112476 0.107431784 0.890407324
1403636985251666432 8.879666328 -0.978777647 6.664820194 -0.013262382 0.442784369 0.105897233 0.890253842
1403636985301666560 8.906513214 -0.982468128 6.710211754 -0.013193294 0.443620056 0.105091192 0.889934242
1403636985351666432 8.932358742 -0.986877680 6.751336575 -0.013547932 0.443105072 0.104119673 0.890299618
1403636985401666560 8.962376595 -0.995656133 6.784040451 -0.014620067 0.440718085 0.102510363 0.891653240
1403636985451666432 8.985652924 -1.004021049 6.827904701 -0.016799761 0.437668443 0.099973060 0.893403292
1403636985501666560 9.004794121 -1.013297796 6.874237061 -0.017508313 0.434079349 0.096759275 0.895492136
1403636985551666432 9.028913498 -1.028015614 6.909402847 -0.017621454 0.429822057 0.094248302 0.897808313
1403636985601666560 9.054924011 -1.037270546 6.951657295 -0.017496753 0.426486403 0.090977967 0.899736702
1403636985651666432 9.071162224 -1.052844048 6.994955063 -0.018165853 0.424490035 0.086902745 0.901069403
1403636985701666560 9.097280502 -1.067655683 7.034909725 -0.017390648 0.422019899 0.083601363 0.902556121
1403636985751666432 9.116312027 -1.083983660 7.075993538 -0.015833875 0.420053780 0.080434546 0.903788924
1403636985801666560 9.138084412 -1.104803801 7.114346504 -0.013701560 0.417706847 0.078232065 0.905103862
1403636985851666432 9.153845787 -1.124522567 7.157847404 -0.006255491 0.416516542 0.074752711 0.906028092
1403636985901666560 9.171560287 -1.147041321 7.197186947 0.003391720 0.415612608 0.069769949 0.906855464
1403636985951666432 9.189334869 -1.169627905 7.238500118 0.014715649 0.414698064 0.065101258 0.907508016
1403636986001666560 9.197897911 -1.177634001 7.286715984 0.022351006 0.415037811 0.061114185 0.907474041
1403636986051666432 9.210002899 -1.192943692 7.326564789 0.024110788 0.414867163 0.057946291 0.907714784
1403636986101666560 9.219671249 -1.204386234 7.362883091 0.022957390 0.413215250 0.059207968 0.908416510
1403636986151666432 9.228289604 -1.205516458 7.408728600 0.017837776 0.412547410 0.061660942 0.908671796
1403636986201666560 9.225999832 -1.207021594 7.452028751 0.011388817 0.411654085 0.065223858 0.908931792
1403636986251666432 9.219111443 -1.216479063 7.487542152 0.001499831 0.411159188 0.068894088 0.908955157
1403636986301666560 9.222890854 -1.218378663 7.532058239 -0.004105060 0.410219163 0.072246127 0.909111619
1403636986351666432 9.222192764 -1.218215704 7.566451550 -0.009009732 0.409157336 0.073678061 0.909439802
1403636986401666560 9.215157509 -1.227834344 7.600672245 -0.011919833 0.407668084 0.078030430 0.909711957
1403636986451666432 9.216149330 -1.222588420 7.645731449 -0.011523184 0.406061351 0.082335010 0.910056233
1403636986501666560 9.209048271 -1.224853158 7.692866325 -0.011926623 0.404887080 0.086274184 0.910209298
1403636986551666432 9.194711685 -1.241107225 7.729200840 -0.010765539 0.403559357 0.091205508 0.910332620
1403636986601666560 9.190721512 -1.243898034 7.769123554 -0.009321615 0.402120411 0.093864478 0.910714984
1403636986651666432 9.183297157 -1.256176949 7.808017731 -0.009011651 0.401374459 0.095738970 0.910852015
1403636986701666560 9.176630020 -1.271542907 7.845697403 -0.008051699 0.399994254 0.099421613 0.911073625
1403636986751666432 9.173526764 -1.280464053 7.883053780 -0.005847384 0.398737431 0.101732567 0.911386192
1403636986801666560 9.166723251 -1.298730135 7.916015625 -0.004823735 0.397446483 0.105394490 0.911539912
1403636986851666432 9.153223991 -1.316962600 7.957395077 -0.003078492 0.398122370 0.105843559 0.911200464
1403636986901666560 9.147927284 -1.338997364 7.982586384 -0.002549106 0.397512168 0.106599934 0.911380291
1403636986951666432 9.137669563 -1.364616513 8.008589745 -0.002484860 0.397953808 0.104882598 0.911387026
1403636987001666560 9.136351585 -1.386889815 8.041786194 -0.002514234 0.398934633 0.103713334 0.911091864
1403636987051666432 9.130510330 -1.414628744 8.070939064 -0.003212350 0.400691241 0.100639813 0.910663426
1403636987101666560 9.124272346 -1.436447620 8.095539093 -0.002789671 0.401688427 0.098554559 0.910453498
1403636987151666432 9.120460510 -1.456976414 8.126724243 -0.002305344 0.402681082 0.097576670 0.910121679
1403636987201666560 9.114385605 -1.480820060 8.149309158 -0.001628948 0.403717101 0.096591093 0.909769237
1403636987251666432 9.111107826 -1.496455431 8.176914215 0.000561506 0.403795511 0.097352460 0.909654558
1403636987301666560 9.099541664 -1.515487432 8.201113701 0.001107151 0.405123770 0.095889837 0.909218729
1403636987351666432 9.090825081 -1.533523917 8.226522446 0.001501230 0.405231684 0.095677331 0.909192443
1403636987401666560 9.083486557 -1.546198368 8.249032974 0.003683930 0.404384524 0.094996363 0.909634709
1403636987451666432 9.075219154 -1.560664892 8.281733513 0.004450432 0.403539747 0.092317149 0.910282016
1403636987501666560 9.064640045 -1.578998327 8.306321144 0.007316608 0.402661890 0.089560382 0.910927474
1403636987551666432 9.054851532 -1.586783409 8.331480026 0.009747819 0.402427435 0.085336782 0.911413610
1403636987601666560 9.043574333 -1.596008301 8.354356766 0.012420234 0.401381284 0.082885280 0.912068427
1403636987651666432 9.035450935 -1.607894421 8.381643295 0.013596212 0.400283456 0.081392616 0.912668347
1403636987701666560 9.022416115 -1.614739180 8.406018257 0.014175237 0.399669588 0.079618476 0.913084984
1403636987751666432 9.005968094 -1.623887062 8.431799889 0.014572933 0.398684919 0.078862891 0.913574576
1403636987801666560 8.991171837 -1.633872271 8.450234413 0.014928310 0.396740854 0.079466924 0.914362550
1403636987851666432 8.974862099 -1.645702839 8.470917702 0.015143965 0.395541877 0.080570400 0.914781749
1403636987901666560 8.958153725 -1.653761387 8.492998123 0.015288312 0.393508196 0.082919054 0.915446281
1403636987951666432 8.942762375 -1.674145579 8.501947403 0.014083199 0.390526414 0.087458134 0.916319728
1403636988001666560 8.921512604 -1.686270595 8.523218155 0.012930400 0.388769656 0.092603482 0.916578174
1403636988051666432 8.900553703 -1.698279619 8.539793015 0.011263548 0.386892855 0.098213628 0.916810274
1403636988101666560 8.879925728 -1.711327076 8.550520897 0.010115406 0.384951800 0.103433795 0.917066634
1403636988151666432 8.861030579 -1.720294476 8.564554214 0.008734424 0.383918464 0.107369281 0.917061687
1403636988201666560 8.840959549 -1.727232456 8.580920219 0.009339212 0.383397490 0.110652998 0.916883290
1403636988251666432 8.821933746 -1.734976530 8.588191986 0.010791114 0.382573724 0.112420812 0.916996419
1403636988301666560 8.805554390 -1.741371870 8.593354225 0.015315495 0.382059336 0.114030465 0.916947722
1403636988351666432 8.787193298 -1.749716759 8.607828140 0.020424979 0.383287877 0.113071203 0.916454136
1403636988401666560 8.773108482 -1.755513668 8.614374161 0.025693163 0.383348495 0.111933477 0.916435897
1403636988451666432 8.759087563 -1.761401892 8.610839844 0.029531954 0.383688152 0.109632112 0.916456223
1403636988501666560 8.737333298 -1.771256804 8.612091064 0.032475501 0.384556592 0.107461751 0.916249692
1403636988551666432 8.720565796 -1.780184150 8.613554955 0.034649238 0.384829938 0.106686354 0.916145921
1403636988601666560 8.703840256 -1.786994457 8.609490395 0.036527257 0.384976417 0.105853014 0.916108072
1403636988651666432 8.689058304 -1.796540380 8.601575851 0.037267815 0.384616971 0.105517454 0.916267931
1403636988701666560 8.670054436 -1.806381583 8.592247963 0.038093638 0.384602904 0.105865613 0.916199744
1403636988751666432 8.652149200 -1.810979366 8.581958771 0.038805906 0.385041177 0.103846788 0.916216791
1403636988801666560 8.640089989 -1.810900688 8.567161560 0.041127872 0.384351611 0.103452973 0.916449547
1403636988851666432 8.618979454 -1.817424178 8.556735039 0.042549506 0.384867042 0.103716895 0.916138470
1403636988901666560 8.601845741 -1.812033296 8.538665771 0.045732856 0.384442061 0.103903502 0.916142404
1403636988951666432 8.584560394 -1.813879132 8.518019676 0.047685020 0.384118676 0.104487836 0.916112065
1403636989001666560 8.560769081 -1.810112119 8.499117851 0.049282033 0.384565681 0.104574002 0.915830076
1403636989051666432 8.545210838 -1.805586457 8.475324631 0.051551282 0.384077758 0.105293877 0.915827453
1403636989101666560 8.522565842 -1.795160174 8.453036308 0.052180655 0.384832263 0.105269924 0.915477753
1403636989151666432 8.505063057 -1.786344647 8.429622650 0.052459739 0.384936929 0.105903238 0.915344775
1403636989201666560 8.484591484 -1.772684813 8.403766632 0.052203961 0.385504872 0.105950288 0.915114939
1403636989251666432 8.461139679 -1.764983654 8.365361214 0.048013054 0.386394709 0.104570553 0.915127814
1403636989301666560 8.437683105 -1.746284962 8.330477715 0.041711789 0.388556540 0.101891771 0.914823472
1403636989351666432 8.413256645 -1.740810037 8.292472839 0.032938480 0.390748560 0.098827668 0.914583862
1403636989401666560 8.393670082 -1.732079387 8.244072914 0.023498699 0.391534716 0.097947471 0.914633632
1403636989451666432 8.369420052 -1.724974871 8.206036568 0.015346387 0.392545730 0.098238885 0.914342046
1403636989501666560 8.343330383 -1.719107628 8.167835236 0.010216912 0.393547028 0.098313101 0.913975298
1403636989551666432 8.320749283 -1.716873646 8.118530273 0.005648033 0.394074529 0.098361827 0.913782418
1403636989601666560 8.297117233 -1.714203000 8.071572304 0.003043155 0.394770235 0.096689135 0.913673043
1403636989651666432 8.272350311 -1.708281994 8.024470329 -0.000220292 0.395515323 0.095100991 0.913522542
1403636989701666560 8.251067162 -1.705248356 7.974055290 -0.003137453 0.396371424 0.092784405 0.913384318
1403636989751666432 8.225820541 -1.696773291 7.933560848 -0.004849479 0.397090793 0.091249004 0.913219035
1403636989801666560 8.200828552 -1.692701936 7.890108109 -0.005944781 0.397200584 0.091111712 0.913178504
1403636989851666432 8.179052353 -1.683073997 7.846789837 -0.005258747 0.396893233 0.091038086 0.913323700
1403636989901666560 8.152889252 -1.675499678 7.808117867 -0.003372952 0.397250801 0.091323726 0.913148582
1403636989951666432 8.126503944 -1.664121270 7.764794350 0.001205420 0.397321612 0.090288818 0.913226128
1403636990001666560 8.105511665 -1.649951100 7.724555016 0.005352900 0.397012204 0.090109989 0.913363457
1403636990051666432 8.081443787 -1.644888520 7.677193642 0.008579474 0.397206813 0.088685609 0.913393676
1403636990101666560 8.058172226 -1.635354996 7.627832413 0.011338415 0.396725893 0.088336065 0.913606465
1403636990151666432 8.025903702 -1.619188309 7.599010468 0.012915282 0.397930145 0.086629421 0.913225114
1403636990201666560 7.996989250 -1.613973379 7.556726933 0.011783349 0.398255885 0.085638545 0.913191915
1403636990251666432 7.973837852 -1.607862473 7.506403923 0.009379917 0.397570282 0.085494749 0.913531899
1403636990301666560 7.946010113 -1.602084160 7.457369328 0.006508809 0.397284389 0.085252583 0.913703859
1403636990351666432 7.912218571 -1.603590250 7.410489559 0.004266512 0.396983773 0.085015453 0.913869798
1403636990401666560 7.888542175 -1.598891973 7.366899490 0.000627147 0.396270603 0.084723368 0.914216101
1403636990451666432 7.855544567 -1.597983599 7.323289394 -0.001038209 0.395394444 0.085874036 0.914487720
1403636990501666560 7.826017380 -1.592479944 7.276254177 -0.003469856 0.393919885 0.087253764 0.914987326
1403636990551666432 7.794332981 -1.586651802 7.230125427 -0.004007316 0.393112212 0.087601647 0.915299237
1403636990601666560 7.764920712 -1.579657674 7.187599659 -0.005704167 0.392255813 0.088164911 0.915603518
1403636990651666432 7.734595299 -1.568704367 7.146741867 -0.007299282 0.391286761 0.088960260 0.915929854
1403636990701666560 7.702932358 -1.559732676 7.102528572 -0.009194918 0.390987992 0.087685920 0.916163206
1403636990751666432 7.673909664 -1.547733307 7.062024117 -0.010271903 0.390364021 0.087817721 0.916405201
1403636990801666560 7.642655849 -1.535387993 7.020591259 -0.010971990 0.390054613 0.087083250 0.916598856
1403636990851666432 7.608622074 -1.527436495 6.980084419 -0.012006870 0.389804214 0.086528130 0.916745007
1403636990901666560 7.584044456 -1.505267382 6.947468758 -0.011429840 0.389403909 0.087284669 0.916850746
1403636990951666432 7.552082062 -1.490839243 6.905137062 -0.012083000 0.389351249 0.086566627 0.916932821
1403636991001666560 7.522308826 -1.470549464 6.865769863 -0.011435667 0.389161110 0.086401850 0.917037368
1403636991051666432 7.491291046 -1.457926750 6.833735943 -0.010566486 0.389708728 0.085359327 0.916912913
1403636991101666560 7.460406780 -1.437761664 6.797109127 -0.011469493 0.389768332 0.085097246 0.916901052
1403636991151666432 7.433297157 -1.414707661 6.760837078 -0.010730237 0.389860153 0.085768372 0.916808426
1403636991201666560 7.404321671 -1.394625425 6.724330902 -0.011515785 0.390434384 0.084973827 0.916628480
1403636991251666432 7.376508236 -1.377835989 6.693889618 -0.011959645 0.390630424 0.085892729 0.916453660
1403636991301666560 7.344394207 -1.364606380 6.662106514 -0.012759602 0.391379893 0.085413449 0.916167855
1403636991351666432 7.317505836 -1.352210283 6.622697353 -0.012186671 0.391030341 0.086973384 0.916178107
1403636991401666560 7.284045696 -1.342184544 6.592229843 -0.013777442 0.391893893 0.086747341 0.915807962
1403636991451666432 7.254350662 -1.330610514 6.557017326 -0.013984327 0.392374843 0.086687051 0.915604591
1403636991501666560 7.223102093 -1.322230101 6.525150299 -0.014443143 0.393314868 0.086990096 0.915165305
1403636991551666432 7.193744183 -1.318243265 6.492621422 -0.013203683 0.393269986 0.088962495 0.915013731
1403636991601666560 7.168046951 -1.313614845 6.461040020 -0.012945293 0.393529385 0.090843566 0.914721012
1403636991651666432 7.133606911 -1.311009645 6.426894188 -0.011348192 0.393461615 0.094209097 0.914430857
1403636991701666560 7.105869293 -1.315103292 6.391160011 -0.010458340 0.392766237 0.099613443 0.914167643
1403636991751666432 7.073032379 -1.318201065 6.355284691 -0.009344966 0.392673194 0.103833102 0.913750052
1403636991801666560 7.044693470 -1.321133375 6.322286129 -0.007662553 0.392674565 0.107604936 0.913328648
1403636991851666432 7.019191742 -1.322210789 6.287749290 -0.006780395 0.392862678 0.111245185 0.912818432
1403636991901666560 6.992628574 -1.319852352 6.256192207 -0.006360032 0.393677652 0.113238178 0.912225068
1403636991951666432 6.963970661 -1.321593046 6.221581936 -0.006536471 0.394760221 0.113139711 0.911768079
1403636992001666560 6.939365387 -1.318384886 6.186762333 -0.007131750 0.396267533 0.112478539 0.911191404
1403636992051666432 6.914548874 -1.310285091 6.166478634 -0.006686448 0.399668425 0.107633375 0.910294175
1403636992101666560 6.891774654 -1.313709974 6.119278908 -0.007010455 0.401463002 0.103269681 0.910007536
1403636992151666432 6.867649555 -1.305750847 6.092658997 -0.005072912 0.403543323 0.099291444 0.909542859
1403636992201666560 6.844783306 -1.298648119 6.070304871 -0.003002009 0.405875832 0.096438348 0.908820927
1403636992251666432 6.824069023 -1.288768411 6.024934292 -0.001755691 0.406664759 0.094718792 0.908652306
1403636992301666560 6.804460049 -1.282904387 5.999987602 -0.002090324 0.407910526 0.093982749 0.908169508
1403636992351666432 6.781357765 -1.267829776 5.967152596 -0.003052224 0.408703417 0.093732968 0.907836080
1403636992401666560 6.762545109 -1.260643482 5.937223434 -0.006259588 0.409290820 0.094492510 0.907476187
1403636992451666432 6.742197037 -1.248746514 5.908047199 -0.009651351 0.409819782 0.095823266 0.907068074
1403636992501666560 6.720430851 -1.240901828 5.880800247 -0.012156797 0.410745561 0.096344970 0.906563818
1403636992551666432 6.694943905 -1.231966496 5.849181652 -0.014439847 0.411955744 0.095886223 0.906029701
1403636992601666560 6.678003311 -1.226802826 5.825559616 -0.015640296 0.412733585 0.096719548 0.905567050
1403636992651666432 6.649744511 -1.225064516 5.789224625 -0.016288174 0.413450003 0.097084664 0.905189693
1403636992701666560 6.626524448 -1.224253297 5.763270855 -0.017457135 0.414878458 0.096922800 0.904531419
1403636992751666432 6.604259014 -1.223869801 5.735575199 -0.018702878 0.415319234 0.097522691 0.904239714
1403636992801666560 6.582015991 -1.220865250 5.706671238 -0.019377854 0.416396141 0.096611865 0.903827906
1403636992851666432 6.559074402 -1.216805935 5.679055214 -0.019311745 0.417398006 0.096115179 0.903420091
1403636992901666560 6.538020134 -1.213652849 5.656339645 -0.020088280 0.418752551 0.094720908 0.902923405
1403636992951666432 6.514295578 -1.209356070 5.629638672 -0.019994261 0.419716895 0.093839139 0.902569771
1403636993001666560 6.494747162 -1.204761267 5.611636639 -0.017659832 0.420503050 0.094114266 0.902223825
1403636993051666432 6.476857185 -1.192692518 5.590939522 -0.014169175 0.421040177 0.094701789 0.901973426
1403636993101666560 6.452189922 -1.186370015 5.569226742 -0.010124394 0.419865102 0.096336044 0.902402461
1403636993151666432 6.428486347 -1.181437969 5.551574230 -0.006336240 0.417189062 0.097511083 0.903551161
1403636993201666560 6.406958103 -1.176711440 5.535135269 -0.004145774 0.413132221 0.097376131 0.905440450
1403636993251666432 6.384131432 -1.174407959 5.512884140 -0.002781032 0.407905191 0.096940160 0.907859206
1403636993301666560 6.358630657 -1.169346571 5.491799831 -0.001366762 0.401935279 0.095317669 0.910692453
1403636993351666432 6.333881855 -1.168592334 5.469910622 -0.000594177 0.394542366 0.093167789 0.914142072
1403636993401666560 6.309168816 -1.173293591 5.445015907 0.000084599 0.386667579 0.091096796 0.917708874
1403636993451666432 6.280808926 -1.174110174 5.426342010 0.000986596 0.378340513 0.088394858 0.921435773
1403636993501666560 6.255067825 -1.180365801 5.403320789 0.000431231 0.369243652 0.085346960 0.925405204
1403636993551666432 6.232018948 -1.184402943 5.374709129 0.000620667 0.359644562 0.081441775 0.929528177
1403636993601666560 6.208892822 -1.191374779 5.351106644 -0.000852484 0.350374818 0.078890853 0.933280766
1403636993651666432 6.179627895 -1.197772384 5.328003883 -0.002716369 0.342296988 0.076176219 0.936494827
1403636993701666560 6.154051304 -1.204009533 5.302008152 -0.004034045 0.335054547 0.074468821 0.939242542
1403636993751666432 6.128362179 -1.207373381 5.284472466 -0.005991719 0.329528958 0.072055362 0.941372812
1403636993801666560 6.098548889 -1.211870551 5.254940033 -0.007046171 0.324671715 0.070716061 0.943153143
1403636993851666432 6.075217247 -1.212108493 5.232613087 -0.007956845 0.321255356 0.067566566 0.944545627
1403636993901666560 6.051169872 -1.209229231 5.211129189 -0.008561328 0.317747355 0.065609515 0.945863962
1403636993951666432 6.025099754 -1.210640430 5.188690186 -0.007044347 0.314923644 0.064490281 0.946897268
1403636994001666560 6.002330303 -1.206190467 5.166311741 -0.004123479 0.313080400 0.062202178 0.947678506
1403636994051666432 5.977564335 -1.200361013 5.147920132 -0.000771131 0.312451601 0.058751736 0.948114753
1403636994101666560 5.953138828 -1.196369648 5.127408028 0.003939096 0.312052429 0.056049090 0.948401928
1403636994151666432 5.923153400 -1.190671921 5.102204800 0.007747863 0.311777681 0.053542029 0.948613703
1403636994201666560 5.901738644 -1.181540489 5.086637020 0.012592967 0.311817557 0.051617678 0.948655248
1403636994251666432 5.874565601 -1.172471642 5.059144020 0.016491570 0.311219305 0.050271314 0.948864222
1403636994301666560 5.844523430 -1.161234617 5.039691448 0.019928416 0.311721236 0.049024954 0.948698699
1403636994351666432 5.814686775 -1.151568770 5.022050858 0.021805782 0.312217891 0.048142605 0.948539257
1403636994401666560 5.792478561 -1.133288980 4.996593952 0.024361297 0.311795950 0.047274355 0.948659539
1403636994451666432 5.757282734 -1.120970488 4.975839615 0.024504980 0.312419266 0.047361061 0.948446393
1403636994501666560 5.724892616 -1.107540965 4.948301315 0.023328379 0.312415421 0.048279837 0.948431015
1403636994551666432 5.688225746 -1.095599055 4.921026230 0.021765655 0.311620623 0.052066162 0.948529363
1403636994601666560 5.652740479 -1.089231968 4.896585941 0.018107757 0.311351359 0.053793389 0.948598266
1403636994651666432 5.622728348 -1.074317336 4.870386600 0.014508135 0.310600787 0.057939429 0.948662043
1403636994701666560 5.579984665 -1.069263935 4.834602356 0.010524820 0.309125960 0.064287893 0.948787332
1403636994751666432 5.543907642 -1.059576869 4.806008816 0.006422190 0.307567179 0.070823215 0.948865235
1403636994801666560 5.507857323 -1.058640003 4.773046494 0.002439404 0.306034446 0.077506833 0.948857009
1403636994851666432 5.471849442 -1.053104639 4.743299484 0.001325920 0.304625183 0.083372712 0.948815465
1403636994901666560 5.432887077 -1.047231913 4.707396507 -0.000059149 0.304155082 0.086859792 0.948654354
1403636994951666432 5.400437832 -1.041038871 4.676728249 0.000619866 0.304094940 0.088385791 0.948532462
1403636995001666560 5.366164207 -1.034471512 4.636929512 0.002485783 0.304404050 0.087514110 0.948511064
1403636995051666432 5.333190918 -1.023659468 4.606914520 0.003899058 0.305776477 0.082926542 0.948477089
1403636995101666560 5.299639702 -1.014263749 4.569011688 0.006975056 0.307117522 0.078356452 0.948414683
1403636995151666432 5.270981789 -1.008206248 4.532479286 0.009017172 0.308099300 0.073985532 0.948430121
1403636995201666560 5.237531185 -0.985669613 4.503967762 0.011133019 0.309230655 0.069701105 0.948363960
1403636995251666432 5.205245018 -0.978594184 4.470516682 0.012585972 0.309671432 0.067313202 0.948374450
1403636995301666560 5.170159340 -0.970779538 4.438271999 0.012822524 0.310264647 0.064506710 0.948372483
1403636995351666432 5.136393070 -0.967117548 4.390223026 0.011713052 0.309906781 0.062828377 0.948616445
1403636995401666560 5.099221230 -0.960953832 4.347349644 0.008891311 0.309467524 0.061281350 0.948891640
1403636995451666432 5.071558952 -0.960837603 4.305806637 0.004803602 0.308657855 0.061806008 0.949150801
1403636995501666560 5.032403946 -0.956633449 4.265546799 0.001363730 0.308210582 0.062597170 0.949255466
1403636995551666432 5.002317429 -0.952000678 4.223344326 0.000891476 0.307346761 0.063526005 0.949474394
1403636995601666560 4.964705944 -0.954633176 4.181125641 -0.001243198 0.307382971 0.063309439 0.949476719
1403636995651666432 4.929968834 -0.958597600 4.141072750 -0.001340287 0.306649715 0.065479018 0.949566543
1403636995701666560 4.894446373 -0.955998063 4.105806351 -0.001007803 0.306856155 0.065280460 0.949513972
1403636995751666432 4.861763000 -0.953378558 4.056625843 -0.000622753 0.305838197 0.067383200 0.949695766
1403636995801666560 4.826358318 -0.953144550 4.012969017 -0.000347313 0.304748476 0.071796127 0.949722886
1403636995851666432 4.792586327 -0.946219623 3.974380016 -0.000900741 0.303405076 0.076558121 0.949780703
1403636995901666560 4.757821560 -0.937203526 3.931761742 -0.001036168 0.302569658 0.081035748 0.949675620
1403636995951666432 4.732097626 -0.938436151 3.892519712 -0.002634821 0.301536441 0.084449336 0.949703693
1403636996001666560 4.702712536 -0.927394927 3.866219759 -0.003175107 0.301788121 0.085843556 0.949497104
1403636996051666432 4.672462463 -0.914774299 3.821192741 -0.005402813 0.302696019 0.083034836 0.949447811
1403636996101666560 4.641393185 -0.905109942 3.773195267 -0.007135791 0.303355247 0.080827393 0.949416459
1403636996151666432 4.609576702 -0.888236046 3.741743088 -0.008124931 0.304984123 0.077370256 0.949174643
1403636996201666560 4.581367493 -0.883202195 3.700269699 -0.010067913 0.305979580 0.074877903 0.949035525
1403636996251666432 4.550879478 -0.876967132 3.661012173 -0.011175026 0.307048649 0.072418474 0.948868692
1403636996301666560 4.528672695 -0.863654137 3.627573729 -0.011277263 0.307029098 0.069859631 0.949065626
1403636996351666432 4.494137764 -0.862967253 3.583128929 -0.012178523 0.305711389 0.068971299 0.949544728
1403636996401666560 4.471211433 -0.857329965 3.545359373 -0.012147485 0.303080708 0.067370258 0.950502872
1403636996451666432 4.444710255 -0.866509557 3.501018047 -0.013672345 0.298843771 0.065507896 0.951952815
1403636996501666560 4.422434807 -0.857892513 3.458337545 -0.012996580 0.293954074 0.062714659 0.953671277
1403636996551666432 4.393671513 -0.865322471 3.413146019 -0.013946717 0.288212895 0.059185125 0.955633759
1403636996601666560 4.358316898 -0.857954741 3.386077166 -0.013838694 0.282016695 0.056901909 0.957620621
1403636996651666432 4.327301502 -0.870638967 3.345983505 -0.015250040 0.273771584 0.053790439 0.960168302
1403636996701666560 4.306009293 -0.867836773 3.312271595 -0.016688544 0.264956027 0.050249308 0.962805688
1403636996751666432 4.279623985 -0.860993266 3.267682076 -0.017266734 0.254612654 0.048092488 0.965692163
1403636996801666560 4.249457836 -0.852409124 3.236366272 -0.018288560 0.244879782 0.043447062 0.968406796
1403636996851666432 4.224484444 -0.841394186 3.202385426 -0.019218026 0.233536333 0.041240618 0.971282959
1403636996901666560 4.197326183 -0.833933890 3.174123049 -0.020287191 0.222195745 0.038703948 0.974022329
1403636996951666432 4.174010277 -0.813294172 3.133791685 -0.019948617 0.209995747 0.036669586 0.976810694
1403636997001666560 4.147275448 -0.807615936 3.107267618 -0.021406230 0.198999688 0.031705774 0.979252577
1403636997051666432 4.122213364 -0.796784818 3.065760374 -0.021898942 0.187578946 0.028321637 0.981596887
1403636997101666560 4.097155571 -0.772132695 3.044706583 -0.022416212 0.177642390 0.025429672 0.983511090
1403636997151666432 4.071549416 -0.766348660 3.016448259 -0.024693416 0.169457361 0.022217130 0.984977603
1403636997201666560 4.055377483 -0.750506401 2.981114864 -0.025159875 0.161223814 0.020740367 0.986379087
1403636997251666432 4.026576042 -0.736054242 2.961368561 -0.026290543 0.156482905 0.017523564 0.987175167
1403636997301666560 4.011051655 -0.714282632 2.926975250 -0.026657926 0.151173949 0.016209347 0.988014698
1403636997351666432 3.990016937 -0.700618446 2.904317617 -0.027282691 0.147540420 0.015177305 0.988563180
1403636997401666560 3.971455097 -0.689176679 2.878447056 -0.028179122 0.145054966 0.013280827 0.988933027
1403636997451666432 3.947902679 -0.678171813 2.852198839 -0.027315727 0.143491507 0.012445990 0.989196181
1403636997501666560 3.931765079 -0.663249910 2.834564209 -0.026984472 0.142626882 0.011340952 0.989343643
1403636997551666432 3.913439274 -0.657973051 2.806478500 -0.027598158 0.141986206 0.011399579 0.989418149
1403636997601666560 3.890198231 -0.651698887 2.797890186 -0.028254790 0.142702252 0.011471127 0.989295781
1403636997651666432 3.877417088 -0.649810553 2.766079426 -0.028406106 0.142485440 0.012027029 0.989316106
1403636997701666560 3.855336666 -0.652543187 2.749005556 -0.029462583 0.143975750 0.010613757 0.989085615
1403636997751666432 3.845021248 -0.652804554 2.711848497 -0.029768012 0.144759625 0.010610255 0.988962054
1403636997801666560 3.817525387 -0.656096816 2.693435192 -0.031083468 0.146604270 0.009889860 0.988657236
1403636997851666432 3.810254097 -0.671212971 2.668573141 -0.031862594 0.147066370 0.009937669 0.988563359
1403636997901666560 3.797607422 -0.682233691 2.651893377 -0.032401767 0.148697600 0.010308546 0.988297999
1403636997951666432 3.777911901 -0.686735034 2.639250278 -0.031729110 0.149896830 0.010723007 0.988134205
1403636998001666560 3.759471178 -0.697314978 2.613973856 -0.031639066 0.151226908 0.010931565 0.987932146
1403636998051666432 3.738989830 -0.718230367 2.604176283 -0.032978911 0.153065905 0.010853686 0.987605929
1403636998101666560 3.722070217 -0.740520477 2.576562405 -0.033194277 0.153667480 0.011613269 0.987496614
1403636998151666432 3.716849566 -0.749316514 2.557125568 -0.031257931 0.153788865 0.012478742 0.987530351
1403636998201666560 3.703210831 -0.765366852 2.535135269 -0.029679062 0.153790846 0.015390294 0.987537682
1403636998251666432 3.681884527 -0.773351550 2.525273323 -0.029836137 0.154787675 0.015723517 0.987371922
1403636998301666560 3.665545225 -0.788143873 2.523865223 -0.030975396 0.156286106 0.015307211 0.987107337
1403636998351666432 3.661371708 -0.801447570 2.500365257 -0.030001322 0.156199113 0.016624486 0.987129867
1403636998401666560 3.640027046 -0.810577333 2.494141817 -0.030174254 0.157085806 0.016539048 0.986985326
1403636998451666432 3.626218796 -0.827378154 2.480683804 -0.030895669 0.157297388 0.017546752 0.986911893
1403636998501666560 3.628177404 -0.828478575 2.464867115 -0.029343570 0.156538278 0.019835494 0.987036586
1403636998551666432 3.605803013 -0.836695850 2.457088232 -0.026467899 0.158047020 0.017422656 0.986923039
1403636998601666560 3.604111195 -0.849872231 2.450483322 -0.023331365 0.157879606 0.017455989 0.987028360
1403636998651666432 3.590110779 -0.867853343 2.430904150 -0.016628487 0.159555092 0.013420844 0.986957729
1403636998701666560 3.588345528 -0.885106802 2.424920082 -0.009924752 0.159680635 0.012725236 0.987036824
1403636998751666432 3.569905519 -0.906734109 2.430795193 -0.004889152 0.160874918 0.010769811 0.986903906
1403636998801666560 3.558629513 -0.924978256 2.404137611 -0.001892870 0.161932990 0.007945399 0.986767948
1403636998851666432 3.549630404 -0.937574208 2.409401894 -0.000131565 0.163594618 0.005087291 0.986514509
1403636998901666560 3.534072161 -0.961140156 2.396655321 0.000113819 0.164861009 0.002579226 0.986313462
1403636998951666432 3.517892122 -0.972616971 2.387548685 -0.000376248 0.166416019 -0.000020613 0.986055553
1403636999001666560 3.501402378 -0.994771481 2.391046047 -0.002140635 0.167675868 -0.002055137 0.985837698
1403636999051666432 3.497486115 -0.993129671 2.369819641 -0.000612674 0.167808965 -0.003021487 0.985814691
1403636999101666560 3.480055809 -1.007900476 2.360408306 -0.002350050 0.168311566 -0.004644308 0.985720098
1403636999151666432 3.458585739 -1.010569930 2.351954222 -0.002927956 0.169685572 -0.005592448 0.985478044
1403636999201666560 3.450232506 -1.010343909 2.350528240 -0.004226949 0.169856280 -0.005085666 0.985446692
1403636999251666432 3.436502218 -1.004787922 2.342747927 -0.004901508 0.169788793 -0.004403174 0.985458434
1403636999301666560 3.424526215 -1.015218496 2.334175587 -0.006928778 0.169291392 -0.002389315 0.985538781
1403636999351666432 3.406802654 -1.019283533 2.303474903 -0.007860791 0.168161973 0.000390136 0.985727966
1403636999401666560 3.388900280 -1.015928388 2.305792809 -0.006999251 0.167249188 0.003064148 0.985885024
1403636999451666432 3.368334055 -1.014594436 2.303776026 -0.006799674 0.166913614 0.005648772 0.985931873
1403636999501666560 3.347298145 -1.011442184 2.294541836 -0.005846149 0.166821077 0.006660855 0.985947371
1403636999551666432 3.326838970 -1.016172290 2.285117149 -0.004196022 0.167024449 0.007371024 0.985916317
1403636999601666560 3.308303833 -1.009175897 2.272789478 -0.002400400 0.166382626 0.007934795 0.986026406
1403636999651666432 3.286797523 -0.998218417 2.269074917 -0.000303202 0.166664630 0.008002709 0.985981107
1403636999701666560 3.274054527 -0.998807311 2.248426914 0.001089807 0.166245475 0.009143560 0.986041427
1403636999751666432 3.252925396 -0.993983030 2.242224693 0.001294360 0.166558921 0.009489403 0.985984981
1403636999801666560 3.231618404 -0.984108984 2.233890295 0.001964109 0.167160839 0.009542084 0.985881507
1403636999851666432 3.203315735 -0.976902306 2.230340242 0.001568738 0.168147504 0.009045232 0.985719144
1403636999901666560 3.187584400 -0.972625494 2.218172312 0.001116463 0.168042406 0.008205866 0.985744953
1403636999951666432 3.170190096 -0.968940079 2.207104206 0.000543278 0.168933615 0.006266853 0.985607326
1403637000001666560 3.150526047 -0.955907226 2.197414637 0.000334271 0.169607326 0.003537680 0.985505283
1403637000051666432 3.125814915 -0.953501642 2.185087919 -0.000826395 0.170348555 0.001013116 0.985383034
1403637000101666560 3.102414608 -0.943387449 2.171425581 -0.001739110 0.170615807 0.000568438 0.985335946
1403637000151666432 3.079361677 -0.937340856 2.160456419 -0.002481141 0.170288086 0.000984164 0.985390723
1403637000201666560 3.054844379 -0.930881679 2.143903732 -0.003618568 0.169728532 0.001831073 0.985482514
1403637000251666432 3.030496120 -0.936611831 2.131143332 -0.005719071 0.169768870 0.002615925 0.985463858
1403637000301666560 3.008079290 -0.932318389 2.108302593 -0.006156788 0.169034630 0.003946073 0.985583007
1403637000351666432 2.981225967 -0.927465558 2.090962410 -0.005756111 0.168856040 0.004441212 0.985613883
1403637000401666560 2.953262568 -0.924292088 2.077372313 -0.004564178 0.168201998 0.006399014 0.985721231
1403637000451666432 2.926109314 -0.917057931 2.064847231 -0.004703037 0.168994606 0.005025435 0.985592961
1403637000501666560 2.897846460 -0.911927998 2.048855305 -0.004864863 0.169420719 0.004264324 0.985522568
1403637000551666432 2.872639656 -0.908963323 2.034111500 -0.005294235 0.169693828 0.003117314 0.985477686
1403637000601666560 2.842913151 -0.907644391 2.021131277 -0.006048950 0.169801965 0.003057476 0.985454917
1403637000651666432 2.818363190 -0.904484391 2.004341125 -0.004401336 0.169073567 0.004663765 0.985582590
1403637000701666560 2.792649031 -0.902315438 1.978654623 -0.003820856 0.168489352 0.005686214 0.985679686
1403637000751666432 2.763486862 -0.900504291 1.959182739 -0.003252830 0.168496177 0.005592539 0.985681057
1403637000801666560 2.732813358 -0.899028420 1.948057890 -0.002218728 0.168862149 0.006050532 0.985618591
1403637000851666432 2.698686361 -0.906322420 1.933151960 -0.002115162 0.169212475 0.006543789 0.985555589
1403637000901666560 2.675437927 -0.903151572 1.908369184 -0.002798328 0.168953910 0.007055235 0.985594749
1403637000951666432 2.649361134 -0.899669111 1.882906199 -0.002853694 0.169231102 0.007544830 0.985543370
1403637001001666560 2.620100975 -0.896072686 1.860808849 -0.001846654 0.169179305 0.007597466 0.985554278
1403637001051666432 2.588897943 -0.892979383 1.844596148 -0.002008921 0.169503048 0.007350678 0.985500216
1403637001101666560 2.560190201 -0.877600849 1.824992537 -0.000686009 0.169371083 0.008923265 0.985511720
1403637001151666432 2.532029629 -0.873402119 1.802688122 -0.000742589 0.169597551 0.008973874 0.985472262
1403637001201666560 2.497586966 -0.868838191 1.784524441 -0.000147785 0.169707671 0.010305490 0.985440552
1403637001251666432 2.465095758 -0.861931920 1.766623020 -0.000240189 0.169765770 0.011427923 0.985418141
1403637001301666560 2.436592340 -0.860913217 1.746163726 -0.000237249 0.169580370 0.011449526 0.985449791
1403637001351666432 2.409134626 -0.856820643 1.722086906 -0.000777150 0.168947205 0.012845051 0.985541105
1403637001401666560 2.373622417 -0.860210299 1.701879382 -0.002702055 0.169064224 0.013985268 0.985502124
1403637001451666432 2.343726635 -0.861461043 1.677199483 -0.005466501 0.169100925 0.014291447 0.985479951
1403637001501666560 2.314801216 -0.859250128 1.647134304 -0.007296716 0.169218019 0.015981810 0.985422015
1403637001551666432 2.283759356 -0.861228168 1.622382402 -0.009009815 0.169613764 0.016355766 0.985333681
1403637001601666560 2.254402161 -0.857739568 1.596033335 -0.009583438 0.170071021 0.016936071 0.985239625
1403637001651666432 2.222799540 -0.858869076 1.572707772 -0.010018366 0.169796064 0.018535823 0.985253990
1403637001701666560 2.194609165 -0.855937302 1.549401045 -0.010127341 0.170579806 0.017548971 0.985135496
1403637001751666432 2.165995598 -0.851870239 1.521549821 -0.009817924 0.171190843 0.017101046 0.985040545
1403637001801666560 2.134639263 -0.846348405 1.494756699 -0.008434382 0.170837432 0.018247122 0.985094130
1403637001851666432 2.108379841 -0.841331840 1.467181802 -0.010473796 0.171530023 0.017997846 0.984958827
1403637001901666560 2.080569267 -0.832692862 1.441850662 -0.011248535 0.171697795 0.018213568 0.984917045
1403637001951666432 2.055574656 -0.823227465 1.416069150 -0.011428121 0.171733528 0.018042026 0.984911919
1403637002001666560 2.023912430 -0.808916926 1.399140954 -0.012360646 0.171980888 0.018343581 0.984851956
1403637002051666432 1.994941950 -0.800093889 1.376862645 -0.013312128 0.172645748 0.017315529 0.984741807
1403637002101666560 1.964063525 -0.789089262 1.354657650 -0.013906609 0.173007011 0.017967662 0.984658480
1403637002151666432 1.939834595 -0.774108410 1.332131147 -0.013317973 0.172563389 0.018529164 0.984734058
1403637002201666560 1.915385008 -0.766736209 1.311553359 -0.014646251 0.172298416 0.017983992 0.984771729
1403637002251666432 1.886043787 -0.748512566 1.291128397 -0.014602944 0.172791451 0.018058147 0.984684587
1403637002301666560 1.859787226 -0.735992610 1.269186020 -0.014784210 0.173320815 0.016237604 0.984620571
1403637002351666432 1.837097168 -0.722632110 1.251677513 -0.014956485 0.173205495 0.015830826 0.984644890
1403637002401666560 1.807142019 -0.712411404 1.235262632 -0.016178241 0.173935935 0.014442696 0.984518170
1403637002451666432 1.784325123 -0.702988863 1.212305903 -0.015645485 0.174060389 0.013058854 0.984524071
1403637002501666560 1.752785802 -0.696139932 1.192169666 -0.015577216 0.174831778 0.011716606 0.984405398
1403637002551666432 1.728762746 -0.683248699 1.166766167 -0.015171838 0.175494492 0.009295623 0.984319627
1403637002601666560 1.700793266 -0.683137238 1.148026347 -0.015063571 0.175690442 0.009055537 0.984288573
1403637002651666432 1.672905922 -0.681484938 1.125698447 -0.015115600 0.175887302 0.008601135 0.984256685
1403637002701666560 1.649876833 -0.676990092 1.099782705 -0.015351371 0.176179186 0.008731131 0.984199703
1403637002751666432 1.618482828 -0.678732097 1.076702833 -0.015773764 0.176826403 0.008912299 0.984075308
1403637002801666560 1.594188452 -0.672944188 1.054298282 -0.014799245 0.176976144 0.009109436 0.984061718
1403637002851666432 1.560248852 -0.673450470 1.034939766 -0.014665614 0.177219883 0.011007237 0.984000444
1403637002901666560 1.536052942 -0.666073203 1.012752652 -0.013259755 0.176688761 0.013935885 0.984078765
1403637002951666432 1.511718750 -0.657255232 0.991454601 -0.013032849 0.176624790 0.014514907 0.984084904
1403637003001666560 1.482993603 -0.653123796 0.973169327 -0.013653418 0.176949143 0.015170028 0.984008372
1403637003051666432 1.451912761 -0.644809604 0.959672511 -0.013921070 0.177819714 0.016175829 0.983831644
1403637003101666560 1.425766230 -0.633867264 0.932043791 -0.014316846 0.178079948 0.016991345 0.983765125
1403637003151666432 1.393017054 -0.624436021 0.924876690 -0.014261320 0.179183915 0.016176704 0.983579218
1403637003201666560 1.366735458 -0.612869501 0.906394422 -0.013970164 0.179684162 0.016956467 0.983478963
1403637003251666432 1.340810776 -0.600887835 0.895112097 -0.013467774 0.180619910 0.016933691 0.983314931
1403637003301666560 1.316884637 -0.586356640 0.872665882 -0.011839850 0.180448174 0.018223673 0.983344376
1403637003351666432 1.290843010 -0.575733662 0.854924083 -0.010843330 0.180346787 0.019525826 0.983349442
1403637003401666560 1.261748195 -0.566158354 0.844779730 -0.009529678 0.181235865 0.018651536 0.983216584
1403637003451666432 1.231099248 -0.560151100 0.823512197 -0.008330891 0.181751564 0.019147377 0.983122706
1403637003501666560 1.206056237 -0.554861903 0.802218437 -0.007761846 0.181854114 0.019611536 0.983099282
1403637003551666432 1.180300474 -0.549359143 0.789009154 -0.007939178 0.181585073 0.020373851 0.983132124
1403637003601666560 1.156565547 -0.542358458 0.772423983 -0.007458502 0.181471497 0.021412697 0.983134747
1403637003651666432 1.128119946 -0.544501483 0.743533611 -0.007614142 0.181887969 0.021813313 0.983047783
1403637003701666560 1.103484988 -0.542285919 0.724294186 -0.007922834 0.181735039 0.021782540 0.983074307
1403637003751666432 1.072228909 -0.536514223 0.707316637 -0.007995452 0.182225376 0.021981953 0.982978523
1403637003801666560 1.052205324 -0.532531142 0.682308435 -0.008279989 0.180620909 0.023623014 0.983234167
1403637003851666432 1.023625612 -0.526165068 0.661861658 -0.009852624 0.180584520 0.023131646 0.983238041
1403637003901666560 0.999132097 -0.527102411 0.634117663 -0.012144401 0.180365264 0.020717116 0.983306527
1403637003951666432 0.972801208 -0.516844988 0.612587690 -0.014648050 0.179724425 0.020237394 0.983399689
1403637004001666560 0.948286653 -0.504955769 0.612038910 -0.016276937 0.179376572 0.019406701 0.983454406
1403637004051666432 0.918240249 -0.494596213 0.596738458 -0.019187024 0.179774567 0.017553225 0.983364046
1403637004101666560 0.891632318 -0.488437593 0.563642323 -0.021114137 0.179078475 0.016683329 0.983466685
1403637004151666432 0.873691440 -0.474281907 0.547651410 -0.021717895 0.178591222 0.015031203 0.983568788
1403637004201666560 0.849232435 -0.461674511 0.530839622 -0.023066740 0.177801192 0.015520639 0.983673632
1403637004251666432 0.822663486 -0.451235473 0.515091240 -0.023713756 0.177225202 0.014721957 0.983774424
1403637004301666560 0.798284173 -0.444792628 0.499552459 -0.023396580 0.175895259 0.016000437 0.984000742
1403637004351666432 0.774076939 -0.438125849 0.484959751 -0.023310710 0.175475150 0.017244643 0.984056771
1403637004401666560 0.750870049 -0.434702665 0.471046239 -0.020877866 0.175012082 0.018735729 0.984166622
1403637004451666432 0.727245986 -0.435345978 0.455812931 -0.018361490 0.175063863 0.019544907 0.984191775
1403637004501666560 0.707144797 -0.435455263 0.443028748 -0.013085989 0.175116330 0.020145416 0.984254599
1403637004551666432 0.678586662 -0.442983747 0.422761261 -0.010371900 0.176851436 0.019228976 0.983995020
1403637004601666560 0.656815052 -0.451354057 0.405825078 -0.009216159 0.177410632 0.021125354 0.983866990
1403637004651666432 0.631363750 -0.460432380 0.387128353 -0.007856360 0.176999554 0.026463684 0.983823717
1403637004701666560 0.606894314 -0.470066726 0.366607130 -0.007319133 0.175999939 0.033252142 0.983801186
1403637004751666432 0.584454060 -0.476075023 0.349044383 -0.006061492 0.176025391 0.038339566 0.983620048
1403637004801666560 0.561790109 -0.479569167 0.331983089 -0.005839342 0.175383240 0.043636587 0.983515322
1403637004851666432 0.543235898 -0.477338791 0.315254986 -0.007186413 0.175722346 0.046479709 0.983315647
1403637004901666560 0.523280323 -0.470912009 0.299136519 -0.010131845 0.176361024 0.048407819 0.983082294
1403637004951666432 0.505650640 -0.461139053 0.285426855 -0.014084203 0.177414492 0.048994888 0.982814908
1403637005001666560 0.489011407 -0.448838204 0.272945195 -0.017997324 0.178954974 0.046696968 0.982583642
1403637005051666432 0.475130737 -0.435582221 0.257136494 -0.019496722 0.180933669 0.043053824 0.982359052
1403637005101666560 0.460123986 -0.422179997 0.242889345 -0.018650983 0.183271989 0.038552720 0.982128918
1403637005151666432 0.447636664 -0.405830890 0.232713789 -0.018189913 0.185776994 0.032829925 0.981874883
1403637005201666560 0.439758480 -0.392129630 0.219894499 -0.017317874 0.186050147 0.031415928 0.981885195
1403637005251666432 0.429784566 -0.377394885 0.206774890 -0.018890291 0.186577216 0.028941128 0.981832206
1403637005301666560 0.416194528 -0.361398488 0.193864197 -0.021384159 0.187401175 0.027843963 0.981655836
1403637005351666432 0.406571269 -0.345397413 0.181701720 -0.023647783 0.187413722 0.027074821 0.981623054
1403637005401666560 0.395054340 -0.329759181 0.172195613 -0.023496475 0.187057853 0.025659101 0.981732607
1403637005451666432 0.387026727 -0.313086152 0.161959454 -0.020834735 0.185726091 0.024489472 0.982075334
1403637005501666560 0.375367880 -0.297659010 0.153977305 -0.018443896 0.185736656 0.021720646 0.982186317
1403637005551666432 0.365247369 -0.283410788 0.145313099 -0.016791876 0.184789002 0.020477105 0.982421339
1403637005601666560 0.353674024 -0.273291290 0.135473013 -0.016886543 0.183502078 0.021243220 0.982644677
1403637005651666432 0.342560887 -0.263734639 0.126092479 -0.020095842 0.181600854 0.023673685 0.982881904
1403637005701666560 0.330304742 -0.259149194 0.115148090 -0.023492608 0.179626033 0.028097112 0.983052969
1403637005751666432 0.320190847 -0.255176276 0.105576500 -0.025423996 0.177967608 0.031011147 0.983218908
1403637005801666560 0.307097644 -0.255735457 0.092848890 -0.025744617 0.177814469 0.030714484 0.983247638
1403637005851666432 0.296940684 -0.257974774 0.082233898 -0.024520962 0.177931979 0.027989179 0.983339012
1403637005901666560 0.286649466 -0.260127485 0.071231775 -0.023286767 0.178363666 0.025728405 0.983352482
1403637005951666432 0.277001649 -0.262008727 0.061530665 -0.021446768 0.178912818 0.023193244 0.983357668
1403637006001666560 0.268512249 -0.262688756 0.052969724 -0.019343944 0.178845063 0.021962481 0.983441889
1403637006051666432 0.259509981 -0.263181359 0.045082428 -0.017362770 0.178919479 0.022630081 0.983450174
1403637006101666560 0.247907579 -0.263662368 0.035489067 -0.015891377 0.178576142 0.023742544 0.983511209
1403637006151666432 0.239745110 -0.262394100 0.027636796 -0.014960029 0.178291738 0.024150888 0.983567476
1403637006201666560 0.230112135 -0.261259645 0.020745680 -0.015572391 0.178082049 0.024403121 0.983589768
1403637006251666432 0.221720681 -0.259967864 0.012668587 -0.018286157 0.177249491 0.026266612 0.983645439
1403637006301666560 0.213369757 -0.257187337 0.007606972 -0.022333272 0.176527441 0.028347982 0.983633935
1403637006351666432 0.202793747 -0.255155087 -0.001885410 -0.028646553 0.175887257 0.030348824 0.983525276
1403637006401666560 0.196376801 -0.252245069 -0.007601112 -0.033355299 0.174709186 0.032705035 0.983511329
1403637006451666432 0.189818054 -0.249971136 -0.012488507 -0.036745250 0.173593491 0.036391966 0.983458519
1403637006501666560 0.183180526 -0.247404724 -0.016332716 -0.037362628 0.172310814 0.039970879 0.983521879
1403637006551666432 0.178182811 -0.245547995 -0.018863993 -0.033759955 0.170321822 0.041876704 0.983919263
1403637006601666560 0.174322978 -0.243759349 -0.021131558 -0.029186189 0.168156251 0.039691780 0.984528422
1403637006651666432 0.171177715 -0.242243826 -0.023507629 -0.024771759 0.164968967 0.036652710 0.985306144
1403637006701666560 0.167729303 -0.239581868 -0.024268134 -0.020825272 0.160873905 0.031585906 0.986249566
1403637006751666432 0.165987864 -0.236347690 -0.024628958 -0.016859660 0.155080482 0.027033629 0.987387955
1403637006801666560 0.166037396 -0.231267512 -0.022570435 -0.013725170 0.147857532 0.023120318 0.988643110
1403637006851666432 0.163067982 -0.226785019 -0.023690347 -0.013737120 0.139614731 0.020139657 0.989905775
1403637006901666560 0.161870331 -0.221586987 -0.025047109 -0.014184255 0.129227370 0.017677793 0.991355956
1403637006951666432 0.160196871 -0.215965107 -0.025937459 -0.016497966 0.119021490 0.011769930 0.992684841
1403637007001666560 0.159490943 -0.209463432 -0.025574639 -0.017428830 0.109059438 0.004701951 0.993871331
1403637007051666432 0.159209341 -0.204349115 -0.026556127 -0.017237548 0.099331751 -0.000496047 0.994904935
1403637007101666560 0.159295589 -0.199098870 -0.028531808 -0.016887588 0.091461837 -0.005250875 0.995651543
1403637007151666432 0.159770966 -0.193492293 -0.028300419 -0.016163381 0.083955690 -0.009890185 0.996289313
1403637007201666560 0.160089806 -0.187607586 -0.028638791 -0.014658550 0.077629521 -0.013521291 0.996782780
1403637007251666432 0.160672352 -0.182609648 -0.029145312 -0.011574256 0.072925590 -0.017827911 0.997110844
1403637007301666560 0.160909772 -0.177355632 -0.029189840 -0.007587896 0.069866464 -0.023345320 0.997254252
1403637007351666432 0.162028641 -0.172404885 -0.030349366 -0.003870934 0.066519365 -0.025771398 0.997444749
1403637007401666560 0.161029384 -0.166162565 -0.032063272 -0.002876187 0.065050669 -0.028743589 0.997463763
1403637007451666432 0.160152510 -0.159721643 -0.033925291 -0.004233206 0.063015543 -0.029067086 0.997580171
1403637007501666560 0.158757940 -0.153197423 -0.036794811 -0.005931595 0.061968029 -0.029642530 0.997620225
1403637007551666432 0.157320246 -0.145386487 -0.039800838 -0.007910075 0.060891651 -0.029295342 0.997683048
1403637007601666560 0.154906973 -0.136698008 -0.042837664 -0.013527227 0.060367346 -0.027724484 0.997699440
1403637007651666432 0.151838154 -0.127937570 -0.046476383 -0.021229384 0.060715009 -0.027431196 0.997552276
1403637007701666560 0.148631960 -0.118736148 -0.049633149 -0.027835866 0.061160896 -0.026152810 0.997396886
1403637007751666432 0.145078793 -0.110826328 -0.053290036 -0.033415243 0.061835669 -0.026207987 0.997182488
1403637007801666560 0.141167313 -0.103637934 -0.054943949 -0.034284718 0.062933393 -0.026664479 0.997072160
1403637007851666432 0.137386799 -0.097761519 -0.056020122 -0.031627186 0.063186616 -0.025396774 0.997177124
1403637007901666560 0.132485762 -0.093864389 -0.057037659 -0.025261385 0.062806025 -0.021247890 0.997479737
1403637007951666432 0.127211332 -0.090124674 -0.058381904 -0.017991461 0.062133893 -0.016729051 0.997765422
1403637008001666560 0.122318387 -0.085649021 -0.058586232 -0.012553187 0.062612876 -0.013971157 0.997861147
1403637008051666432 0.117533408 -0.081399888 -0.060008008 -0.011045089 0.064066559 -0.014469391 0.997779608
1403637008101666560 0.112642974 -0.075763367 -0.062338762 -0.016083453 0.066231050 -0.016248303 0.997542381
1403637008151666432 0.108745426 -0.069823742 -0.064761281 -0.024007827 0.067584842 -0.015606344 0.997302532
1403637008201666560 0.105000719 -0.065032646 -0.066705778 -0.032172501 0.069064625 -0.015347802 0.996975124
1403637008251666432 0.100794695 -0.060967229 -0.068589494 -0.038570561 0.070754491 -0.016434252 0.996612251
1403637008301666560 0.097045787 -0.058529992 -0.069637105 -0.043457124 0.072366253 -0.017932739 0.996269584
1403637008351666432 0.092241071 -0.057394173 -0.070227690 -0.045471307 0.074471645 -0.019174304 0.996001303
1403637008401666560 0.087751128 -0.057729412 -0.069025248 -0.043432329 0.075274058 -0.019001728 0.996035337
1403637008451666432 0.082551911 -0.060957316 -0.067512944 -0.036681227 0.075583965 -0.017343065 0.996313572
1403637008501666560 0.077733979 -0.064937793 -0.064805031 -0.029936712 0.075769790 -0.015422953 0.996556520
1403637008551666432 0.072023317 -0.069257423 -0.062828846 -0.023671104 0.075895995 -0.013549668 0.996742666
1403637008601666560 0.067153484 -0.072535895 -0.058995508 -0.018590413 0.076176926 -0.011234869 0.996857703
1403637008651666432 0.062448502 -0.075046659 -0.055597227 -0.015593671 0.076300286 -0.009744808 0.996915340
1403637008701666560 0.057526805 -0.076688282 -0.052515376 -0.014329171 0.075595513 -0.004586123 0.997025073
1403637008751666432 0.052495550 -0.076563351 -0.048727617 -0.015581639 0.074363060 0.002477831 0.997106433
1403637008801666560 0.048925981 -0.075388886 -0.045589790 -0.019552257 0.071911499 0.011631378 0.997151494
1403637008851666432 0.046382546 -0.073051795 -0.041783698 -0.022868995 0.069896154 0.018582795 0.997118950
1403637008901666560 0.045175277 -0.069351748 -0.037958395 -0.025822086 0.069670692 0.022115402 0.996990502
1403637008951666432 0.046560176 -0.065821342 -0.033782363 -0.027411472 0.069536425 0.023745265 0.996919990
1403637009001666560 0.049797460 -0.060848270 -0.027778719 -0.026765240 0.071418151 0.020102115 0.996884644
1403637009051666432 0.054124750 -0.055054393 -0.022427762 -0.026043024 0.074363947 0.013838940 0.996794999
1403637009101666560 0.060230590 -0.048641570 -0.016045883 -0.025407281 0.077108763 0.007134611 0.996673405
1403637009151666432 0.066806808 -0.041543774 -0.010137003 -0.024485292 0.079955667 0.000735525 0.996497393
1403637009201666560 0.074745610 -0.034216858 -0.003743092 -0.024425637 0.082274117 -0.005563193 0.996294856
1403637009251666432 0.083050840 -0.026275938 0.003277442 -0.025135145 0.085421853 -0.014407874 0.995923579
1403637009301666560 0.091048345 -0.017702455 0.011249194 -0.026167868 0.088891461 -0.023899166 0.995410681
1403637009351666432 0.098421983 -0.009285703 0.019838121 -0.026029188 0.091922015 -0.032949492 0.994880497
1403637009401666560 0.101558715 -0.008824264 0.018436924 -0.019168517 0.077840455 -0.019105462 0.996598423
1403637009451666432 0.107985891 -0.005984983 0.018471643 -0.017714504 0.070747130 -0.025497243 0.997011006
1403637009501666560 0.110557422 -0.006436408 0.017450210 -0.005513464 0.058794521 -0.023343207 0.997981906
1403637009551666432 0.112906940 -0.004450817 0.017063092 0.008444973 0.043033995 -0.010151462 0.998986363
1403637009601666560 0.113538578 -0.004775224 0.015208424 0.034975540 0.032449134 0.003608476 0.998854697
1403637009651666432 0.102091633 -0.006766115 -0.007292492 0.037800141 0.035840396 0.013429818 0.998552084
1403637009701666560 0.077835299 -0.015086090 -0.046199508 0.023317717 0.047821015 0.017316423 0.998433530
1403637009751666432 0.082472235 -0.022180511 -0.026448872 0.020025378 0.052528229 0.015715530 0.998294950
1403637009801666560 0.093364619 -0.021854322 -0.015581576 0.023196636 0.052566286 0.013112371 0.998261869
1403637009851666432 0.101159856 -0.020539565 -0.010314235 0.023498135 0.050648022 0.015180351 0.998324692
1403637009901666560 0.104820549 -0.022904450 -0.006643160 0.023205215 0.051020410 0.012800854 0.998345912
1403637009951666432 0.104309112 -0.022574447 -0.006580018 0.023825800 0.050301645 0.014860115 0.998339236
1403637010001666560 0.104387090 -0.022755055 -0.006806744 0.023507264 0.051029239 0.012540563 0.998341680
1403637010051666432 0.103574634 -0.023202809 -0.006921288 0.023748020 0.050562762 0.013883717 0.998341978
1403637010101666560 0.104263559 -0.022780064 -0.006994720 0.023531806 0.050495356 0.013777775 0.998351932
1403637010151666432 0.103932574 -0.022692068 -0.006278980 0.023582671 0.050738674 0.013381019 0.998343825
1403637010201666560 0.104999095 -0.022752058 -0.006633711 0.023500610 0.050348654 0.013437058 0.998364747
1403637010251666432 0.103532642 -0.022587843 -0.007501313 0.023373956 0.050454259 0.013329307 0.998363853
1403637010301666560 0.104716241 -0.022907248 -0.006595643 0.023353372 0.050150361 0.013954591 0.998371065
1403637010351666432 0.103502929 -0.022365510 -0.007929222 0.023408849 0.050375268 0.013773037 0.998360991
1403637010401666560 0.104690194 -0.022413846 -0.007403506 0.023561224 0.050255116 0.013541200 0.998366594
1403637010451666432 0.104259185 -0.022508245 -0.008080283 0.023385737 0.050648157 0.013144305 0.998356164
1403637010501666560 0.104455672 -0.022718025 -0.006851108 0.023471229 0.050564393 0.013222131 0.998357415
1403637010551666432 0.104219861 -0.022356428 -0.008483216 0.023440549 0.050377700 0.013504850 0.998363793
1403637010601666560 0.104330845 -0.022859829 -0.005860433 0.023508720 0.050489735 0.013438798 0.998357415
================================================
FILE: Examples/Stereo/euroc_old/CameraTrajectory_MH03.txt
================================================
1403637130538319104 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 1.000000000
1403637130588318976 -0.000085505 -0.000044086 -0.000190103 0.000129996 -0.000088065 0.000336573 0.999999940
1403637130638319104 -0.000122778 -0.000133867 0.000113016 -0.000148605 -0.000364574 0.000179546 0.999999881
1403637130688318976 0.000094704 -0.000180682 0.000215388 0.000093266 0.000055331 -0.000098342 1.000000000
1403637130738319104 -0.000046446 -0.000102375 -0.000090888 0.000141978 -0.000059549 0.000257627 0.999999940
1403637130788318976 0.000155430 -0.000052061 0.000237034 -0.000021421 0.000117089 -0.000025394 1.000000000
1403637130838319104 -0.000014811 -0.000010994 0.000071202 -0.000039586 -0.000042840 -0.000079318 1.000000000
1403637130888318976 0.000121439 -0.000118476 0.000136893 -0.000050175 -0.000024965 -0.000105159 1.000000000
1403637130938319104 -0.000048849 -0.000066418 -0.000112974 0.000038182 -0.000055960 0.000161855 1.000000000
1403637130988318976 0.000092467 -0.000005791 0.000012627 0.000036413 -0.000065558 -0.000013503 1.000000000
1403637131038319104 0.000294948 -0.000027302 0.000149271 -0.000006179 0.000077910 -0.000174010 1.000000000
1403637131088318976 0.000420850 0.000067577 0.000850164 0.000104957 0.000060014 -0.000848232 0.999999642
1403637131138319104 -0.000034754 0.000042193 -0.000227424 0.000076800 -0.000041124 0.000080287 1.000000000
1403637131188318976 -0.000089992 -0.000161584 0.000015710 -0.000084751 -0.000221337 0.000152010 0.999999940
1403637131238319104 0.000051706 -0.000107730 -0.000122094 0.000001983 -0.000210260 0.000100144 1.000000000
1403637131288318976 -0.000084731 -0.000046789 0.000200383 0.000001849 -0.000136081 0.000239636 0.999999940
1403637131338319104 0.000046491 0.000008617 0.000039339 0.000026719 -0.000008709 0.000006633 1.000000000
1403637131388318976 -0.000017655 -0.000175368 -0.000308374 -0.000112511 -0.000156625 0.000321007 0.999999940
1403637131438319104 -0.000308253 -0.000072594 -0.000188568 0.000045634 -0.000212252 0.000052918 0.999999940
1403637131488318976 -0.000028102 -0.000238989 0.000133834 -0.000113021 -0.000297159 -0.000139310 0.999999940
1403637131538319104 0.000016166 -0.000043272 -0.000091529 -0.000014567 -0.000044389 0.000028489 1.000000000
1403637131588318976 -0.000045398 -0.000075327 -0.000274642 0.000076584 -0.000004946 0.000359654 0.999999940
1403637131638319104 -0.000133114 -0.000254209 -0.000044851 0.000029188 -0.000267964 0.000576332 0.999999821
1403637131688318976 -0.000273072 -0.000136418 -0.000005290 -0.000066454 -0.000275775 0.000353443 0.999999881
1403637131738319104 0.000024694 -0.000053716 -0.000081722 -0.000010846 -0.000040163 0.000010787 1.000000000
1403637131788318976 -0.000176253 -0.000056164 0.000098450 0.000024326 -0.000179785 0.000174297 0.999999940
1403637131838319104 0.000004054 -0.000170707 0.000205236 0.000003580 -0.000299958 0.000487412 0.999999821
1403637131888318976 -0.000046147 0.000037189 -0.000110161 0.000131768 -0.000010395 0.000305420 0.999999940
1403637131938319104 -0.000033187 -0.000009655 0.000060815 0.000131655 -0.000092623 0.000451477 0.999999881
1403637131988318976 -0.000065472 -0.000033072 -0.000171378 -0.000050659 -0.000136746 0.000034938 1.000000000
1403637132038319104 0.000037128 -0.000002231 0.000559411 0.000065385 0.000050058 -0.000243182 0.999999940
1403637132088318976 0.000099576 -0.000036602 -0.000008575 0.000040159 0.000104984 -0.000250801 0.999999940
1403637132138319104 0.000355979 0.000131291 0.000018412 0.000150376 0.000192057 -0.000524648 0.999999821
1403637132188318976 0.000212519 0.000071217 -0.000161824 0.000035316 0.000063338 -0.000176449 1.000000000
1403637132238319104 0.000212196 -0.000004485 0.000106905 0.000151422 0.000085501 -0.000349778 0.999999940
1403637132288318976 0.000128986 0.000076344 0.000048939 0.000095117 0.000104019 -0.000509543 0.999999881
1403637132338319104 0.000128835 0.000036412 0.000094852 0.000036727 0.000186872 -0.000430821 0.999999881
1403637132388318976 -0.000165059 -0.000065487 -0.000232732 0.000131693 -0.000155238 0.000221894 0.999999940
1403637132438319104 0.000023584 -0.000085512 -0.000018630 0.000028808 0.000054551 -0.000129850 1.000000000
1403637132488318976 0.000051303 -0.000022695 0.000039381 0.000079463 0.000089172 -0.000334308 0.999999940
1403637132538319104 -0.000032421 -0.000136572 -0.000022589 -0.000064491 0.000000309 -0.000162796 1.000000000
1403637132588318976 0.000310874 -0.000092968 0.000305723 -0.000017886 0.000185266 -0.000897945 0.999999583
1403637132638319104 0.000364601 0.000000574 0.000285931 -0.000039186 0.000181956 -0.000727297 0.999999702
1403637132688318976 0.000126113 -0.000165565 0.000145722 0.000036140 0.000064259 -0.000084456 1.000000000
1403637132738319104 0.000035098 -0.000057915 -0.000032910 0.000006756 0.000050772 -0.000086475 1.000000000
1403637132788318976 0.000209117 -0.000279213 -0.000094851 0.000072806 0.000058285 -0.000085731 1.000000000
1403637132838319104 0.000137513 -0.000234420 -0.000050880 0.000155636 -0.000006795 0.000019207 1.000000000
1403637132888318976 0.000176755 -0.000584878 0.000497580 0.000341343 0.000230216 0.000205597 0.999999881
1403637132938319104 0.000347826 -0.000368820 0.000535483 0.000554310 0.000555120 -0.000268899 0.999999642
1403637132988318976 0.000037490 -0.000776956 0.000497317 0.000151180 0.000411409 0.001238810 0.999999166
1403637133038319104 0.000250324 -0.000727341 0.001009500 0.000000742 0.000559305 0.001592914 0.999998569
1403637133088318976 -0.000263610 -0.000770304 0.000080996 0.000590512 0.000488016 0.000881574 0.999999285
1403637133138319104 -0.000383856 -0.001171385 -0.001524441 0.001814108 -0.001264875 0.002594684 0.999994159
1403637133188318976 -0.000365736 -0.002063876 -0.002769566 0.001987648 -0.000615482 0.001410580 0.999996841
1403637133238319104 0.002588804 -0.002976630 0.000593315 0.002129611 0.001661912 -0.001711016 0.999994874
1403637133288318976 0.001736682 -0.004745955 -0.003191496 0.001355148 0.003243818 -0.003807998 0.999986589
1403637133338319104 0.001416211 -0.007730691 -0.006391543 0.000165613 0.004913175 -0.005188314 0.999974489
1403637133388318976 0.002703937 -0.012270010 -0.006794753 -0.001477403 0.008404332 -0.004840047 0.999951899
1403637133438319104 0.003838117 -0.016897598 -0.007270401 -0.004346851 0.010965523 -0.004571831 0.999920011
1403637133488318976 0.003201532 -0.020068383 -0.010194627 -0.008797774 0.010717511 -0.003418828 0.999898016
1403637133538319104 0.003553699 -0.022606816 -0.011381366 -0.014215331 0.012953775 -0.001699612 0.999813616
1403637133588318976 0.004961181 -0.024860449 -0.012394281 -0.019079722 0.015083433 -0.000006177 0.999704182
1403637133638319104 0.006858928 -0.027916664 -0.013467736 -0.022112332 0.017587015 0.000622389 0.999600589
1403637133688318976 0.009735984 -0.033192996 -0.015372041 -0.023913549 0.020139731 -0.000274876 0.999511123
1403637133738319104 0.011122293 -0.041443087 -0.020209361 -0.024299026 0.022578735 -0.000993777 0.999449253
1403637133788318976 0.012340736 -0.052774582 -0.024646478 -0.024063937 0.025395898 -0.000959225 0.999387324
1403637133838319104 0.013617834 -0.068232693 -0.028473565 -0.025317641 0.030624649 -0.000736583 0.999210000
1403637133888318976 0.014510606 -0.089100190 -0.033851836 -0.028061453 0.035819773 0.000603151 0.998964012
1403637133938319104 0.014353357 -0.114473030 -0.039543878 -0.030682545 0.039170593 0.002254039 0.998758793
1403637133988318976 0.012989297 -0.143603191 -0.048439186 -0.032268442 0.043170258 0.002687178 0.998542845
1403637134038319104 0.011579590 -0.174973771 -0.055552937 -0.031423017 0.046323102 0.001119011 0.998431504
1403637134088318976 0.010238491 -0.208124593 -0.063538812 -0.030994462 0.050693989 -0.002951910 0.998228788
1403637134138319104 0.007977836 -0.239218026 -0.072351515 -0.029668612 0.056371011 -0.006762851 0.997946024
1403637134188318976 0.007009365 -0.271239489 -0.079014033 -0.027454579 0.061993077 -0.011233899 0.997635663
1403637134238319104 0.005211018 -0.302240193 -0.085201599 -0.021836501 0.068141967 -0.015206945 0.997320712
1403637134288318976 0.002882224 -0.329984069 -0.091305420 -0.013831987 0.070049703 -0.016445646 0.997312009
1403637134338319104 -0.000515954 -0.356453538 -0.099917948 -0.005355720 0.071032256 -0.017541816 0.997305393
1403637134388318976 0.000585365 -0.373947650 -0.101834536 0.003731769 0.071584262 -0.017287998 0.997277737
1403637134438319104 0.000357515 -0.385581642 -0.102548748 0.010898829 0.073589109 -0.015594049 0.997107148
1403637134488318976 -0.001868242 -0.393984824 -0.104108684 0.014839188 0.074035369 -0.010738627 0.997087359
1403637134538319104 -0.000670041 -0.394305646 -0.104429275 0.014941314 0.074930675 -0.007076823 0.997051716
1403637134588318976 0.000245463 -0.382680327 -0.099822380 0.011988316 0.076298498 -0.006339413 0.996992767
1403637134638319104 0.004207879 -0.364018619 -0.093156785 0.005979764 0.077714510 -0.007920736 0.996926248
1403637134688318976 0.009566082 -0.337320864 -0.083402514 -0.001772528 0.078102224 -0.009818456 0.996895432
1403637134738319104 0.013760718 -0.306524605 -0.074202478 -0.012192612 0.076268405 -0.010183229 0.996960759
1403637134788318976 0.019705739 -0.270319343 -0.064822637 -0.024356266 0.073233798 -0.009344496 0.996973515
1403637134838319104 0.021380816 -0.232844591 -0.057320207 -0.037648279 0.070806496 -0.007105419 0.996753991
1403637134888318976 0.025356628 -0.196219742 -0.047640353 -0.051141504 0.067808829 -0.004289762 0.996377468
1403637134938319104 0.027666457 -0.159082443 -0.039701201 -0.061298743 0.066586234 0.000475362 0.995895803
1403637134988318976 0.028703248 -0.128593475 -0.033612091 -0.067338549 0.064117111 0.005095012 0.995654821
1403637135038319104 0.029559163 -0.103985198 -0.030262949 -0.070927307 0.063040026 0.007558284 0.995458782
1403637135088318976 0.030841833 -0.083460473 -0.026325289 -0.072830938 0.062062770 0.009456611 0.995366514
1403637135138319104 0.032628976 -0.068051480 -0.024588402 -0.075765952 0.061294191 0.009142770 0.995197952
1403637135188318976 0.033158109 -0.058580570 -0.025156286 -0.080761403 0.061466563 0.007151078 0.994810700
1403637135238319104 0.033805270 -0.058407534 -0.026545055 -0.088401556 0.061947387 0.005124278 0.994143546
1403637135288318976 0.033583116 -0.067271829 -0.029931795 -0.095374651 0.062671535 0.004683189 0.993455589
1403637135338319104 0.032977242 -0.086771339 -0.034636877 -0.096863531 0.064553693 0.004137037 0.993193448
1403637135388318976 0.032632995 -0.116845757 -0.040407572 -0.092598878 0.066572428 0.002228293 0.993472993
1403637135438319104 0.031748481 -0.152691215 -0.048459314 -0.083615437 0.068724938 -0.001384755 0.994124413
1403637135488318976 0.030975338 -0.193822965 -0.056068212 -0.071965702 0.071914308 -0.006682012 0.994788706
1403637135538319104 0.030437227 -0.234476537 -0.062137581 -0.059373688 0.073896132 -0.009587317 0.995450735
1403637135588318976 0.027901856 -0.279464126 -0.071226716 -0.048312638 0.077691145 -0.013749633 0.995711267
1403637135638319104 0.024950568 -0.323454320 -0.081344455 -0.037831269 0.082151435 -0.016039280 0.995772421
1403637135688318976 0.023793390 -0.362391204 -0.088286325 -0.026568670 0.084592812 -0.015415625 0.995941997
1403637135738319104 0.019537902 -0.399972707 -0.096585430 -0.016969025 0.085395433 -0.013401168 0.996112466
1403637135788318976 0.017062182 -0.429322094 -0.103255168 -0.008591391 0.084849395 -0.009632741 0.996310174
1403637135838319104 0.015399063 -0.450108260 -0.109283909 -0.003027133 0.084613174 -0.007208776 0.996383190
1403637135888318976 0.017862042 -0.461733788 -0.107147858 0.000322350 0.084130898 -0.004200200 0.996445775
1403637135938319104 0.018734436 -0.464803666 -0.106843568 0.000306110 0.085001424 -0.002897060 0.996376574
1403637135988318976 0.019061211 -0.456073493 -0.102468170 -0.001904382 0.084320098 -0.002517412 0.996433735
1403637136038319104 0.020237496 -0.437967241 -0.098302878 -0.006006395 0.083348252 -0.003154397 0.996497393
1403637136088318976 0.022219807 -0.410797715 -0.088107511 -0.011284732 0.083574936 -0.004711033 0.996426463
1403637136138319104 0.021556403 -0.380148023 -0.078576252 -0.017612111 0.084195100 -0.005140518 0.996280372
1403637136188318976 0.023417089 -0.343234241 -0.067109749 -0.026155999 0.085548967 -0.007929699 0.995959044
1403637136238319104 0.026261225 -0.302107185 -0.054103330 -0.035992801 0.085506909 -0.006840058 0.995663762
1403637136288318976 0.027515180 -0.260522127 -0.043136731 -0.048449744 0.085208513 -0.006949473 0.995160222
1403637136338319104 0.029982757 -0.221418440 -0.034653388 -0.061702676 0.085217506 -0.005293482 0.994435906
1403637136388318976 0.030562490 -0.180876240 -0.027286181 -0.074408807 0.083536036 -0.002166488 0.993720472
1403637136438319104 0.031276196 -0.144685969 -0.022568069 -0.086360849 0.081458166 0.000316885 0.992928147
1403637136488318976 0.032008674 -0.119329229 -0.019588774 -0.096439160 0.078300267 0.005326155 0.992240012
1403637136538319104 0.032370433 -0.098777585 -0.018325664 -0.103315510 0.075793952 0.009081685 0.991715074
1403637136588318976 0.033172037 -0.088096142 -0.017460056 -0.107997373 0.074443392 0.011906402 0.991288543
1403637136638319104 0.033027556 -0.087158993 -0.019118421 -0.110683203 0.074069463 0.011272920 0.991027653
1403637136688318976 0.032798972 -0.097487435 -0.023283551 -0.112204544 0.074298866 0.008757450 0.990864813
1403637136738319104 0.031857397 -0.118731022 -0.029186921 -0.111715212 0.073899835 0.009083351 0.990947008
1403637136788318976 0.030087221 -0.151178300 -0.039134141 -0.108533636 0.074036598 0.007918798 0.991300285
1403637136838319104 0.028308164 -0.190603212 -0.048482426 -0.101017214 0.073412850 0.006321188 0.992152274
1403637136888318976 0.026427422 -0.237831444 -0.058238696 -0.090718836 0.075128049 0.003760670 0.993031561
1403637136938319104 0.025784036 -0.288648009 -0.069191888 -0.078553066 0.077895932 0.003117908 0.993857086
1403637136988318976 0.026629731 -0.335114270 -0.076938212 -0.065850109 0.083798312 0.000772989 0.994304299
1403637137038319104 0.024462087 -0.382012129 -0.088489935 -0.053518470 0.089340180 0.000868662 0.994561911
1403637137088318976 0.025252631 -0.421735406 -0.095680967 -0.040567387 0.093896821 0.002208321 0.994752645
1403637137138319104 0.020959130 -0.455661476 -0.107037760 -0.028258469 0.095073558 0.006781830 0.995045960
1403637137188318976 0.020440212 -0.481546640 -0.112062156 -0.017784324 0.093539178 0.011181954 0.995393932
1403637137238319104 0.020842142 -0.495072454 -0.115456976 -0.010362920 0.091828771 0.011526760 0.995654166
1403637137288318976 0.021022338 -0.498117298 -0.115490243 -0.005601421 0.091717690 0.010659814 0.995712221
1403637137338319104 0.022897182 -0.490868300 -0.112675391 -0.002171594 0.091664173 0.009554164 0.995741785
1403637137388318976 0.023897279 -0.474102736 -0.107340537 -0.000570441 0.090912431 0.007810868 0.995828092
1403637137438319104 0.024384102 -0.449283540 -0.098421246 -0.001055999 0.089393422 0.007587173 0.995966911
1403637137488318976 0.026443150 -0.417011678 -0.088687956 -0.005640225 0.089053839 0.005249110 0.995997012
1403637137538319104 0.028540550 -0.377764076 -0.076999888 -0.013895715 0.088617392 0.001804604 0.995967150
1403637137588318976 0.031221919 -0.333618671 -0.065119743 -0.025349367 0.090248369 -0.002437392 0.995593667
1403637137638319104 0.032118089 -0.292597681 -0.053887736 -0.040554088 0.092974186 -0.006248128 0.994822681
1403637137688318976 0.034224723 -0.248951748 -0.041834559 -0.055336487 0.094618507 -0.006309002 0.993954420
1403637137738319104 0.034102127 -0.207335159 -0.034110591 -0.068638168 0.093323857 -0.004046646 0.993258774
1403637137788318976 0.033964552 -0.168240428 -0.026988894 -0.079184890 0.090374276 -0.000888782 0.992754459
1403637137838319104 0.034872420 -0.131623745 -0.023795445 -0.087024860 0.086633772 0.001521966 0.992430806
1403637137888318976 0.034968939 -0.105024904 -0.022506852 -0.094801135 0.082595453 0.002944167 0.992059529
1403637137938319104 0.035341289 -0.086909488 -0.022182757 -0.103103980 0.081275105 0.001772062 0.991342962
1403637137988318976 0.036584493 -0.079910435 -0.023595650 -0.112127706 0.080298141 0.001307067 0.990443289
1403637138038319104 0.037372641 -0.083470620 -0.025224948 -0.119611368 0.079922833 0.001541593 0.989597380
1403637138088318976 0.037929203 -0.101968706 -0.031896163 -0.122842118 0.078747600 0.003736370 0.989289999
1403637138138319104 0.037930846 -0.130386680 -0.036739960 -0.120613672 0.075681970 0.003945050 0.989802539
1403637138188318976 0.038729593 -0.167464465 -0.045771562 -0.113240033 0.074189760 -0.001681728 0.990792453
1403637138238319104 0.039937291 -0.213684306 -0.053750508 -0.102152780 0.077290989 -0.011626806 0.991693377
1403637138288318976 0.040015101 -0.263487667 -0.066608936 -0.086898737 0.081074461 -0.018207980 0.992745697
1403637138338319104 0.039767709 -0.313123792 -0.075171277 -0.069298081 0.084561706 -0.020323008 0.993797779
1403637138388318976 0.036380298 -0.358980924 -0.081747316 -0.050438151 0.089568585 -0.020439245 0.994492710
1403637138438319104 0.034559555 -0.401883453 -0.092776388 -0.033456232 0.094952531 -0.021657949 0.994683683
1403637138488318976 0.031221474 -0.436676562 -0.101400554 -0.019576192 0.100070044 -0.021927256 0.994546056
1403637138538319104 0.030916974 -0.462114185 -0.106025845 -0.008765135 0.103162870 -0.020517210 0.994414210
1403637138588318976 0.031256430 -0.474559069 -0.106290706 -0.000771731 0.104909420 -0.020493073 0.994270325
1403637138638319104 0.032423675 -0.482112110 -0.109063573 0.003456363 0.104311153 -0.018994242 0.994357288
1403637138688318976 0.032569736 -0.476862997 -0.108180568 0.003923910 0.103213362 -0.017871466 0.994490921
1403637138738319104 0.034575395 -0.459016860 -0.099884048 0.002188536 0.101342954 -0.014808942 0.994738936
1403637138788318976 0.035987422 -0.433270097 -0.090321407 -0.002416725 0.101050876 -0.012308137 0.994802177
1403637138838319104 0.038166799 -0.404002547 -0.080370694 -0.009606688 0.102114744 -0.010035864 0.994675577
1403637138888318976 0.040702466 -0.364238739 -0.065583616 -0.018370099 0.102572501 -0.008984426 0.994515300
1403637138938319104 0.043608621 -0.322241515 -0.052050263 -0.027010126 0.100805327 -0.008878576 0.994499803
1403637138988318976 0.044860773 -0.282208681 -0.041380286 -0.033795886 0.095251761 -0.003634650 0.994872689
1403637139038319104 0.046344001 -0.238327041 -0.025815614 -0.039155096 0.088715859 0.001491391 0.995285988
1403637139088318976 0.048450168 -0.197601959 -0.014102601 -0.043611906 0.082781486 0.006888314 0.995589137
1403637139138319104 0.047816660 -0.160523936 -0.004988487 -0.047753297 0.078738183 0.009934908 0.995701373
1403637139188318976 0.046824563 -0.127617687 0.002608577 -0.051922619 0.074430563 0.012802094 0.995791256
1403637139238319104 0.045787260 -0.098805346 0.011527795 -0.055053018 0.071664467 0.012622262 0.995828331
1403637139288318976 0.045086406 -0.076691732 0.018876120 -0.056269448 0.069165751 0.012231701 0.995941877
1403637139338319104 0.044744212 -0.061135143 0.024281405 -0.057355437 0.067218117 0.010813389 0.996029735
1403637139388318976 0.044890910 -0.049811248 0.029216252 -0.058487419 0.065412737 0.007725100 0.996112823
1403637139438319104 0.044816207 -0.042084951 0.032287281 -0.058127377 0.060765035 0.005938960 0.996440470
1403637139488318976 0.044418126 -0.036100227 0.034934022 -0.056349002 0.055982251 0.004535392 0.996830046
1403637139538319104 0.043429498 -0.032288190 0.037053268 -0.053921126 0.052192450 0.004696975 0.997169197
1403637139588318976 0.042450316 -0.028871084 0.038924284 -0.050781805 0.050271347 0.004299866 0.997434497
1403637139638319104 0.041706141 -0.025726549 0.040729403 -0.047688060 0.049085878 0.001852662 0.997653723
1403637139688318976 0.041373674 -0.022166012 0.042559568 -0.045105375 0.047104981 0.000834400 0.997870684
1403637139738319104 0.041584715 -0.018499266 0.044351358 -0.043589935 0.045517515 0.000193623 0.998012066
1403637139788318976 0.041594241 -0.014550949 0.045385327 -0.042877704 0.045647919 -0.001102154 0.998036325
1403637139838319104 0.042541016 -0.012561472 0.044992723 -0.039788689 0.044962417 0.000784697 0.998195708
1403637139888318976 0.044152133 -0.012213579 0.045365427 -0.032506473 0.045756053 0.001135735 0.998422980
1403637139938319104 0.044971354 -0.011635892 0.044474367 -0.027134931 0.047607116 0.003430787 0.998491645
1403637139988318976 0.045280326 -0.011194311 0.043821748 -0.023362737 0.049976289 0.006718574 0.998454511
1403637140038319104 0.046399377 -0.010739646 0.043048721 -0.018126061 0.052127551 0.011051927 0.998414755
1403637140088318976 0.047270380 -0.011225734 0.041525826 -0.012577877 0.055654239 0.010080134 0.998319983
1403637140138319104 0.048067059 -0.011539958 0.040481601 -0.006255755 0.058665372 0.010679248 0.998201013
1403637140188318976 0.049341895 -0.011547039 0.040063899 -0.002752882 0.060050782 0.011435346 0.998126030
1403637140238319104 0.050787847 -0.010618434 0.039679300 -0.004259066 0.062690519 0.011558604 0.997956991
1403637140288318976 0.051017556 -0.010203661 0.039176930 -0.004668156 0.063920446 0.012285862 0.997868478
1403637140338319104 0.052340962 -0.009515366 0.039472014 -0.003283468 0.063259862 0.014770179 0.997882366
1403637140388318976 0.051421244 -0.010152712 0.038660210 -0.003688169 0.063222803 0.016614661 0.997854352
1403637140438319104 0.051940724 -0.009760117 0.039072834 -0.003388041 0.062987283 0.015797237 0.997883558
1403637140488318976 0.051255066 -0.010053391 0.038803138 -0.003573910 0.063005105 0.016916851 0.997863412
1403637140538319104 0.051658425 -0.009942153 0.039240122 -0.003185524 0.062815972 0.016878393 0.997877300
1403637140588318976 0.051348425 -0.010069029 0.038487449 -0.003093591 0.062237587 0.018402416 0.997886896
1403637140638319104 0.051474825 -0.010069403 0.038545221 -0.003147436 0.062243398 0.018066181 0.997892499
1403637140688318976 0.051335838 -0.010099614 0.038358666 -0.003119786 0.062137067 0.018111873 0.997898400
1403637140738319104 0.051125601 -0.010194553 0.038368843 -0.003466611 0.062458523 0.018099910 0.997877419
1403637140788318976 0.051077999 -0.010222516 0.038344413 -0.003535511 0.062392529 0.018285844 0.997877896
1403637140838319104 0.051050678 -0.010224945 0.038552821 -0.003527774 0.062447865 0.018145468 0.997877061
1403637140888318976 0.050695494 -0.010191759 0.038328655 -0.003517812 0.062514842 0.018341197 0.997869313
1403637140938319104 0.051020160 -0.010232523 0.038349379 -0.003551120 0.062432185 0.018358277 0.997874022
1403637140988318976 0.050933037 -0.010180429 0.038696691 -0.003572374 0.062540643 0.018144362 0.997871101
1403637141038319104 0.051234480 -0.010126369 0.038690615 -0.003172559 0.062162634 0.018168956 0.997895598
1403637141088318976 0.051636741 -0.009983493 0.038907148 -0.003037069 0.062046845 0.018449968 0.997898102
1403637141138319104 0.051687766 -0.009872972 0.038991310 -0.003078261 0.062047172 0.018281126 0.997901022
1403637141188318976 0.051471647 -0.009972923 0.038983189 -0.003136744 0.062115520 0.018468225 0.997893155
1403637141238319104 0.051649429 -0.009990338 0.038893480 -0.003009652 0.062068764 0.018305130 0.997899473
1403637141288318976 0.051322564 -0.010100154 0.038783785 -0.003140770 0.062103827 0.018299054 0.997896969
1403637141338319104 0.051240474 -0.009973623 0.038426451 -0.002966483 0.062047917 0.018326296 0.997900486
1403637141388318976 0.050816573 -0.010216793 0.038127512 -0.003500341 0.062406205 0.018354138 0.997875929
1403637141438319104 0.050786581 -0.010112783 0.038504280 -0.003479908 0.062582567 0.018122984 0.997869194
1403637141488318976 0.051342770 -0.009961431 0.038867332 -0.002996409 0.062121641 0.018252157 0.997897208
1403637141538319104 0.051456057 -0.010094164 0.038432632 -0.003034587 0.062062398 0.018303679 0.997899771
1403637141588318976 0.051184911 -0.010301148 0.038683329 -0.003579694 0.062377881 0.018417118 0.997876227
1403637141638319104 0.050759908 -0.010177918 0.038583599 -0.003482001 0.062540762 0.018314559 0.997868299
1403637141688318976 0.051490653 -0.010040571 0.039004542 -0.003027952 0.062051147 0.018451495 0.997897804
1403637141738319104 0.051418826 -0.010008156 0.038787559 -0.002970707 0.062082369 0.018442085 0.997896194
1403637141788318976 0.051626172 -0.009900946 0.039227758 -0.002982041 0.062114298 0.018464606 0.997893810
1403637141838319104 0.051482946 -0.009987371 0.038649403 -0.002954140 0.062086027 0.018523749 0.997894526
1403637141888318976 0.051487699 -0.009938850 0.039000019 -0.003000550 0.062131647 0.018365078 0.997894466
1403637141938319104 0.050939716 -0.010222320 0.038381971 -0.003434428 0.062389530 0.018531971 0.997873902
1403637141988318976 0.051482134 -0.009962169 0.038858768 -0.002928355 0.062066209 0.018547473 0.997895420
1403637142038319104 0.050944403 -0.010277223 0.038648233 -0.003420464 0.062463105 0.018513329 0.997869670
1403637142088318976 0.050880846 -0.010098627 0.038729191 -0.003376134 0.062430821 0.018514480 0.997871816
1403637142138319104 0.051418666 -0.009903053 0.038837310 -0.003022488 0.062084842 0.018584283 0.997893274
1403637142188318976 0.051345058 -0.009867817 0.038798962 -0.002937793 0.062125247 0.018513625 0.997892320
1403637142238319104 0.050750423 -0.009943248 0.038375102 -0.003427291 0.062609933 0.018183688 0.997866511
1403637142288318976 0.050771069 -0.010042821 0.038484134 -0.003419061 0.062687457 0.018103968 0.997863173
1403637142338319104 0.050937973 -0.010021942 0.038419615 -0.003405508 0.062511466 0.018298360 0.997870684
1403637142388318976 0.050864484 -0.009972085 0.038588699 -0.003374192 0.062517576 0.018228862 0.997871697
1403637142438319104 0.051505968 -0.009875000 0.038876873 -0.002926823 0.062070530 0.018522615 0.997895598
1403637142488318976 0.051170591 -0.010181966 0.038757712 -0.003448986 0.062512375 0.018337127 0.997869730
1403637142538319104 0.050926168 -0.010197773 0.038604662 -0.003383592 0.062453348 0.018564651 0.997869492
1403637142588318976 0.051492278 -0.010077760 0.038944703 -0.003008560 0.062230755 0.018235259 0.997890651
1403637142638319104 0.050868906 -0.010187582 0.038404487 -0.003445953 0.062508926 0.018598892 0.997865140
1403637142688318976 0.050937716 -0.010190161 0.038525511 -0.003400671 0.062421780 0.018601054 0.997870743
1403637142738319104 0.050755482 -0.010206602 0.038284779 -0.003376113 0.062465176 0.018582841 0.997868419
1403637142788318976 0.051013276 -0.010018405 0.038730916 -0.003292247 0.062531009 0.018222163 0.997871220
1403637142838319104 0.051067017 -0.010194783 0.038796149 -0.003423402 0.062440921 0.018451512 0.997872233
1403637142888318976 0.051556692 -0.009890152 0.038819280 -0.002901266 0.062079690 0.018747730 0.997890890
1403637142938319104 0.051131513 -0.010084089 0.038850531 -0.003359821 0.062441468 0.018731084 0.997867167
1403637142988318976 0.050882913 -0.010183755 0.038457718 -0.003393242 0.062485129 0.018520666 0.997868240
1403637143038319104 0.050985944 -0.010125495 0.038447466 -0.003392265 0.062474132 0.018665036 0.997866273
1403637143088318976 0.050954890 -0.010239488 0.038644493 -0.003394099 0.062465940 0.018533384 0.997869253
1403637143138319104 0.050720543 -0.010169283 0.038525410 -0.003424832 0.062440272 0.018651124 0.997868538
1403637143188318976 0.050867379 -0.010106334 0.038577743 -0.003371952 0.062533066 0.018553495 0.997864723
1403637143238319104 0.051080391 -0.010167382 0.038816947 -0.003419252 0.062530920 0.018622665 0.997863412
1403637143288318976 0.050826944 -0.010265158 0.038289052 -0.003473754 0.062497567 0.018669119 0.997864425
1403637143338319104 0.050839864 -0.010239284 0.038316537 -0.003461923 0.062512845 0.018615713 0.997864544
1403637143388318976 0.050657988 -0.010123781 0.038308203 -0.003425935 0.062537991 0.018581046 0.997863710
1403637143438319104 0.050732028 -0.010185543 0.038291685 -0.003397190 0.062491205 0.018652873 0.997865438
1403637143488318976 0.050772797 -0.010182282 0.038249049 -0.003326187 0.062544055 0.018595995 0.997863412
1403637143538319104 0.050791226 -0.010088246 0.038335126 -0.003455852 0.062559605 0.018556379 0.997862697
1403637143588318976 0.050750166 -0.010159567 0.038372122 -0.003214751 0.062513821 0.018605430 0.997865498
1403637143638319104 0.050735500 -0.010043323 0.038255174 -0.003347884 0.062508203 0.018557055 0.997866273
1403637143688318976 0.050565053 -0.010136179 0.038204946 -0.003384420 0.062597342 0.018669350 0.997858524
1403637143738319104 0.050859194 -0.010190225 0.038728282 -0.003362869 0.062604174 0.018599352 0.997859478
1403637143788318976 0.051048882 -0.010174957 0.038773183 -0.003300510 0.062408447 0.018672079 0.997870564
1403637143838319104 0.050915875 -0.010143722 0.038602892 -0.003357463 0.062511347 0.018514527 0.997866869
1403637143888318976 0.051113278 -0.010119258 0.038859062 -0.003304845 0.062452730 0.018688256 0.997867465
1403637143938319104 0.050899122 -0.009933164 0.039005630 -0.003314705 0.062400434 0.018440330 0.997875333
1403637143988318976 0.050782390 -0.010130590 0.038417999 -0.003408064 0.062370587 0.018517978 0.997875452
1403637144038319104 0.050697904 -0.010125191 0.038385272 -0.003388374 0.062404200 0.018369898 0.997876167
1403637144088318976 0.050840788 -0.010129735 0.037868366 -0.003304185 0.062329009 0.018716378 0.997874677
1403637144138319104 0.051007919 -0.010097819 0.039253533 -0.003337896 0.062522024 0.018718451 0.997862458
1403637144188318976 0.050915740 -0.010072757 0.038653150 -0.003406056 0.062560163 0.018567163 0.997862697
1403637144238319104 0.051113401 -0.010129308 0.038828053 -0.003525625 0.062562995 0.018812122 0.997857451
1403637144288318976 0.050822377 -0.010000411 0.038165491 -0.003520378 0.062694177 0.018524505 0.997854650
1403637144338319104 0.050840311 -0.010249010 0.038394753 -0.003472424 0.062646911 0.018786730 0.997852862
1403637144388318976 0.051592760 -0.010142421 0.039052431 -0.002961913 0.062219530 0.018723514 0.997882426
1403637144438319104 0.051349804 -0.009928270 0.039098326 -0.002749510 0.062163141 0.018690536 0.997887194
1403637144488318976 0.051485121 -0.010024871 0.039086539 -0.002735063 0.062133934 0.018730635 0.997888327
1403637144538319104 0.051432867 -0.010021208 0.038960390 -0.002710083 0.062112492 0.018714748 0.997889996
1403637144588318976 0.051542707 -0.009981728 0.038722441 -0.002924646 0.062368952 0.018930312 0.997869372
1403637144638319104 0.051414456 -0.010131594 0.038668737 -0.002885682 0.062094051 0.018871462 0.997887731
1403637144688318976 0.051333964 -0.009948350 0.039013263 -0.002982321 0.062217861 0.018675592 0.997883379
1403637144738319104 0.051464032 -0.010048252 0.039039679 -0.002930196 0.062253077 0.018454520 0.997885466
1403637144788318976 0.051457230 -0.009993345 0.038885262 -0.002744637 0.062014498 0.018958731 0.997891426
1403637144838319104 0.051488258 -0.009996457 0.038671408 -0.002788321 0.062081426 0.018705672 0.997891903
1403637144888318976 0.050771233 -0.010213058 0.038934715 -0.003222428 0.062457204 0.018561516 0.997869790
1403637144938319104 0.050812159 -0.010148303 0.038696233 -0.003319305 0.062333666 0.018457513 0.997879148
1403637144988318976 0.050565571 -0.010288939 0.038148362 -0.003476427 0.062157579 0.018319614 0.997892141
1403637145038319104 0.051019996 -0.009992906 0.038864829 -0.003422420 0.062255707 0.018307187 0.997886479
1403637145088318976 0.051616702 -0.009976502 0.039013218 -0.003009293 0.061930809 0.018488871 0.997904658
1403637145138319104 0.050847441 -0.010096425 0.038538955 -0.003479314 0.062387697 0.018641545 0.997871816
1403637145188318976 0.050855614 -0.010045995 0.038434673 -0.003448619 0.062461983 0.018639455 0.997867286
1403637145238319104 0.050829608 -0.010151805 0.037882686 -0.003408250 0.062530637 0.018781297 0.997860491
1403637145288318976 0.050790247 -0.010074569 0.038433038 -0.003484471 0.062581800 0.018540859 0.997861505
1403637145338319104 0.050846424 -0.010145505 0.038208708 -0.003386910 0.062568173 0.018628348 0.997861087
1403637145388318976 0.050926555 -0.010163727 0.038369354 -0.003417703 0.062506817 0.018735195 0.997862816
1403637145438319104 0.050950311 -0.010142627 0.038660035 -0.003415693 0.062526032 0.018615173 0.997863889
1403637145488318976 0.050811172 -0.010307589 0.038316410 -0.003474916 0.062483009 0.018688440 0.997865021
1403637145538319104 0.050881155 -0.010164639 0.038644347 -0.003407612 0.062501244 0.018791566 0.997862160
1403637145588318976 0.050889179 -0.010112034 0.038694467 -0.003338879 0.062576726 0.018717006 0.997859061
1403637145638319104 0.051501699 -0.009955149 0.038788036 -0.002950992 0.062148266 0.018585945 0.997889519
1403637145688318976 0.051490720 -0.010084541 0.038708106 -0.003030322 0.062093168 0.018393785 0.997896254
1403637145738319104 0.051000722 -0.010188040 0.038570788 -0.003323337 0.062333338 0.018734694 0.997874022
1403637145788318976 0.051409986 -0.009892670 0.038705964 -0.002923683 0.062072720 0.018527178 0.997895360
1403637145838319104 0.051091865 -0.010085302 0.038545206 -0.003389014 0.062406145 0.018676588 0.997870326
1403637145888318976 0.050973296 -0.010314962 0.038254455 -0.003455863 0.062452506 0.018582642 0.997868955
1403637145938319104 0.050958749 -0.010115849 0.038686778 -0.003350029 0.062501974 0.018691244 0.997864187
1403637145988318976 0.051517069 -0.009991406 0.038866665 -0.002986224 0.062125169 0.018552162 0.997891486
1403637146038319104 0.051572409 -0.009930746 0.039113928 -0.002890086 0.062074274 0.018727710 0.997891665
1403637146088318976 0.051582418 -0.009985239 0.039021108 -0.002965521 0.062179130 0.018502105 0.997889102
1403637146138319104 0.050882149 -0.010171819 0.038278669 -0.003512709 0.062631078 0.018381311 0.997861266
1403637146188318976 0.051508352 -0.010042786 0.038714886 -0.003037406 0.062133782 0.018482428 0.997892082
1403637146238319104 0.052006599 -0.009963067 0.039226297 -0.002961714 0.062359639 0.017990420 0.997887194
1403637146288318976 0.051309347 -0.009986491 0.038848326 -0.002832987 0.062098879 0.018749116 0.997889876
1403637146338319104 0.051727645 -0.009876982 0.038833600 -0.002828605 0.062216606 0.018090505 0.997894704
1403637146388318976 0.051407043 -0.010024703 0.039205037 -0.002861378 0.062143974 0.018498810 0.997891665
1403637146438319104 0.051528439 -0.009896823 0.038721323 -0.002992490 0.062278982 0.017994050 0.997892082
1403637146488318976 0.051076531 -0.010165798 0.038856443 -0.003371157 0.062485497 0.018619511 0.997866452
1403637146538319104 0.050864212 -0.010120917 0.038154032 -0.003368545 0.062636651 0.018237038 0.997864068
1403637146588318976 0.050896011 -0.010256766 0.038586743 -0.003459886 0.062501617 0.018634057 0.997864902
1403637146638319104 0.050820913 -0.010007091 0.038398150 -0.003311849 0.062584981 0.018211395 0.997868001
1403637146688318976 0.050891012 -0.010193618 0.038708463 -0.003322680 0.062550761 0.018476741 0.997865200
1403637146738319104 0.050750777 -0.010032943 0.038499251 -0.003415202 0.062571920 0.018500647 0.997863114
1403637146788318976 0.051535830 -0.009937031 0.039054222 -0.002908314 0.062126786 0.018481174 0.997892916
1403637146838319104 0.051496763 -0.009934746 0.038936455 -0.002893378 0.062162675 0.018347111 0.997893214
1403637146888318976 0.051046383 -0.010194184 0.038393497 -0.003387318 0.062447280 0.018587342 0.997869432
1403637146938319104 0.051466934 -0.009884818 0.038801108 -0.002886445 0.062176023 0.018422320 0.997891009
1403637146988318976 0.051305369 -0.009830371 0.038480096 -0.002773884 0.062268618 0.018138001 0.997890770
1403637147038319104 0.051567417 -0.009905419 0.038633768 -0.002956252 0.062017489 0.018494280 0.997899354
1403637147088318976 0.050823212 -0.010007839 0.038140509 -0.003379696 0.062480859 0.018406847 0.997870684
1403637147138319104 0.050882362 -0.010103072 0.038209271 -0.003390446 0.062534608 0.018420378 0.997867048
1403637147188318976 0.051460143 -0.009874292 0.038806837 -0.002884012 0.062062517 0.018520325 0.997896254
1403637147238319104 0.051521804 -0.009922281 0.038758490 -0.002876085 0.062135633 0.018577121 0.997890711
1403637147288318976 0.051495072 -0.009924589 0.038575858 -0.002924342 0.062079512 0.018624276 0.997893155
1403637147338319104 0.051071294 -0.010145196 0.038357310 -0.003339126 0.062462665 0.018474672 0.997870684
1403637147388318976 0.051026709 -0.010203751 0.038231511 -0.003446724 0.062478278 0.018532841 0.997868299
1403637147438319104 0.050922289 -0.010091775 0.038229447 -0.003404339 0.062696464 0.018085143 0.997862935
1403637147488318976 0.050859392 -0.010128854 0.038288314 -0.003391898 0.062497061 0.018414009 0.997869492
1403637147538319104 0.051499218 -0.009901338 0.038596574 -0.002888692 0.062174723 0.018328793 0.997892797
1403637147588318976 0.050923176 -0.010281744 0.038236659 -0.003345114 0.062496107 0.018292876 0.997871935
1403637147638319104 0.051348008 -0.009821554 0.038876753 -0.002819003 0.062211540 0.018180978 0.997893393
1403637147688318976 0.051264916 -0.009924307 0.038723696 -0.002861571 0.062183190 0.018295940 0.997892976
1403637147738319104 0.051452857 -0.009940731 0.039039649 -0.002920401 0.062244229 0.018210111 0.997890532
1403637147788318976 0.050864413 -0.010234426 0.038481943 -0.003346561 0.062581368 0.018201360 0.997868299
1403637147838319104 0.051061291 -0.010198046 0.039039902 -0.003304492 0.062543049 0.018422969 0.997866750
1403637147888318976 0.051120564 -0.010231137 0.038702842 -0.003434055 0.062539548 0.018351607 0.997867823
1403637147938319104 0.050966576 -0.009916880 0.038565181 -0.003286408 0.062630929 0.018034671 0.997868419
1403637147988318976 0.051382024 -0.009885778 0.038817707 -0.002919031 0.062172450 0.018415976 0.997891247
1403637148038319104 0.051058140 -0.010147667 0.038447220 -0.003309875 0.062557228 0.018242395 0.997869194
1403637148088318976 0.051428735 -0.009989819 0.038679909 -0.002810806 0.062258694 0.018096158 0.997892022
1403637148138319104 0.050915729 -0.010169988 0.038301736 -0.003224240 0.062649831 0.018159473 0.997865140
1403637148188318976 0.051321212 -0.010058234 0.038449362 -0.002834941 0.062268205 0.018286666 0.997887909
1403637148238319104 0.051427223 -0.009908209 0.038486682 -0.002949452 0.062122855 0.018268932 0.997896969
1403637148288318976 0.050917417 -0.010196016 0.038149208 -0.003205971 0.062456544 0.018246535 0.997875750
1403637148338319104 0.050928500 -0.010104623 0.038475119 -0.003485246 0.062389478 0.018157199 0.997880578
1403637148388318976 0.050877538 -0.010173583 0.038668018 -0.003340022 0.062398534 0.018272910 0.997878432
1403637148438319104 0.051828749 -0.009988012 0.039071269 -0.002926820 0.061878141 0.018257188 0.997912407
1403637148488318976 0.051072404 -0.010159759 0.038459226 -0.003573357 0.062195085 0.018136330 0.997892857
1403637148538319104 0.050960071 -0.010147291 0.038684271 -0.003494340 0.062080182 0.017897999 0.997904539
1403637148588318976 0.051404912 -0.009911941 0.038846523 -0.003054173 0.061411306 0.018131366 0.997943163
1403637148638319104 0.051322836 -0.009908641 0.038916949 -0.003452130 0.061208889 0.017665632 0.997962654
1403637148688318976 0.051367104 -0.009818524 0.038520392 -0.003368816 0.060561046 0.017946618 0.997997463
1403637148738319104 0.050629586 -0.009857509 0.037944216 -0.004112877 0.060885504 0.017325820 0.997985899
1403637148788318976 0.051207215 -0.009869252 0.038480267 -0.003768460 0.060148701 0.017660884 0.998026073
1403637148838319104 0.050602581 -0.009835195 0.037726443 -0.004222244 0.060270604 0.017021656 0.998028040
1403637148888318976 0.050835643 -0.009727502 0.037870176 -0.004521167 0.059668809 0.017269919 0.998058617
1403637148938319104 0.050803475 -0.009826033 0.037427209 -0.004678358 0.059576362 0.016814524 0.998071194
1403637148988318976 0.051054608 -0.009651572 0.037638050 -0.004176695 0.058792900 0.017302137 0.998111486
1403637149038319104 0.051099565 -0.009728573 0.037906978 -0.004617073 0.058594905 0.016769987 0.998130322
1403637149088318976 0.050670281 -0.009726016 0.037707962 -0.005080990 0.058687478 0.016803827 0.998122036
1403637149138319104 0.050906390 -0.009676972 0.037921425 -0.005132347 0.058395024 0.016451670 0.998144805
1403637149188318976 0.050619781 -0.009849125 0.037060287 -0.005428534 0.058150277 0.016184362 0.998161852
1403637149238319104 0.050733492 -0.009792746 0.037310738 -0.005219384 0.057804588 0.016422404 0.998179197
1403637149288318976 0.050673522 -0.009777720 0.037253074 -0.005504820 0.057535741 0.016424377 0.998193145
1403637149338319104 0.050768852 -0.009766037 0.037466124 -0.005651385 0.057040386 0.016221328 0.998224080
1403637149388318976 0.050697841 -0.009682530 0.037039809 -0.005861999 0.056737483 0.015956385 0.998244405
1403637149438319104 0.051589716 -0.009499821 0.037539341 -0.005579479 0.055519391 0.015995847 0.998313904
1403637149488318976 0.051558398 -0.009425257 0.037171103 -0.005985606 0.054800157 0.015898814 0.998352826
1403637149538319104 0.051057529 -0.009377298 0.036689937 -0.006988084 0.054523554 0.015016615 0.998375118
1403637149588318976 0.050993357 -0.009168831 0.035617277 -0.009284409 0.052579612 0.013821494 0.998477876
1403637149638319104 0.051112048 -0.008646399 0.035068460 -0.013901714 0.048967883 0.011208684 0.998640716
1403637149688318976 0.051417850 -0.007722133 0.034045789 -0.017859396 0.043237079 0.008356694 0.998870254
1403637149738319104 0.052200913 -0.007340800 0.032599337 -0.019325702 0.040417150 0.006853513 0.998972476
1403637149788318976 0.052378476 -0.007152925 0.031788930 -0.023364656 0.038630173 0.006712951 0.998957813
1403637149838319104 0.053391263 -0.007340285 0.031226913 -0.028739410 0.036980253 0.006563382 0.998881102
1403637149888318976 0.055883169 -0.007293429 0.030981837 -0.037167959 0.036414612 0.007328264 0.998618484
1403637149938319104 0.059848558 -0.007339155 0.029134182 -0.046354663 0.037223157 0.004993428 0.998218834
1403637149988318976 0.064758047 -0.008277534 0.027153041 -0.056984447 0.038565457 0.000861752 0.997629583
1403637150038319104 0.071557410 -0.011305476 0.025819881 -0.067199707 0.041560993 -0.006927249 0.996849477
1403637150088318976 0.079183780 -0.016614966 0.024622776 -0.075697951 0.044765286 -0.011908811 0.996054292
1403637150138319104 0.087344751 -0.024253547 0.024595164 -0.081224628 0.048289105 -0.016599651 0.995386958
1403637150188318976 0.096179955 -0.035059467 0.026166990 -0.082732275 0.051960856 -0.020288642 0.995009422
1403637150238319104 0.104370654 -0.047548369 0.028515661 -0.081635915 0.055146907 -0.022137467 0.994889081
1403637150288318976 0.113501236 -0.062951498 0.034122534 -0.077768117 0.057670303 -0.022095343 0.995056808
1403637150338319104 0.122068062 -0.079836726 0.040127788 -0.073402502 0.060112271 -0.021822285 0.995249927
1403637150388318976 0.130829617 -0.098501094 0.048011821 -0.064581275 0.061506402 -0.019459076 0.995825052
1403637150438319104 0.138404891 -0.116635360 0.055041574 -0.057825364 0.062992088 -0.017895106 0.996176720
1403637150488318976 0.147536397 -0.134816617 0.064900458 -0.053397648 0.065140098 -0.017670132 0.996289730
1403637150538319104 0.155337647 -0.152810171 0.074070461 -0.050363068 0.067142591 -0.017470401 0.996318340
1403637150588318976 0.164659008 -0.169173241 0.084628284 -0.048846584 0.068709359 -0.017195987 0.996291757
1403637150638319104 0.173756331 -0.187698632 0.095091715 -0.047547031 0.069902293 -0.016462993 0.996284068
1403637150688318976 0.183562711 -0.203667328 0.107685432 -0.047063123 0.071078464 -0.016430803 0.996224344
1403637150738319104 0.189216301 -0.219466314 0.115475878 -0.046858501 0.072488546 -0.016996831 0.996122897
1403637150788318976 0.199236572 -0.233466133 0.129305139 -0.046217207 0.073087819 -0.017176481 0.996105969
1403637150838319104 0.204297006 -0.249689788 0.136653602 -0.044864669 0.074530646 -0.018004116 0.996046305
1403637150888318976 0.214640930 -0.264268696 0.150706992 -0.040794946 0.074860819 -0.018814046 0.996181548
1403637150938319104 0.222775698 -0.280160457 0.163980901 -0.036869384 0.075108759 -0.019268377 0.996307194
1403637150988318976 0.230177984 -0.293663174 0.176973596 -0.033110723 0.075290874 -0.019775117 0.996415496
1403637151038319104 0.238870353 -0.305095941 0.190544948 -0.029455332 0.074834488 -0.020127499 0.996557593
1403637151088318976 0.245705858 -0.314924687 0.202323362 -0.025772259 0.074548855 -0.020462953 0.996674240
1403637151138319104 0.255296260 -0.325396657 0.213567346 -0.021371035 0.073697306 -0.021660430 0.996816337
1403637151188318976 0.261021554 -0.333462983 0.223082319 -0.020232871 0.073032632 -0.022319425 0.996874452
1403637151238319104 0.268286496 -0.342617929 0.233128563 -0.023043254 0.072118230 -0.021618469 0.996895492
1403637151288318976 0.272794247 -0.354214370 0.240365699 -0.026588613 0.070798926 -0.020057309 0.996934414
1403637151338319104 0.277008593 -0.366905659 0.247436747 -0.030705288 0.068685696 -0.016301548 0.997032464
1403637151388318976 0.280358374 -0.383879066 0.248981595 -0.034539972 0.066397280 -0.010857749 0.997136116
1403637151438319104 0.287172347 -0.402081847 0.256042838 -0.037443105 0.064379610 -0.005853107 0.997205615
1403637151488318976 0.291892618 -0.419221371 0.263175011 -0.039200906 0.064442568 -0.007963036 0.997119367
1403637151538319104 0.297389001 -0.437912226 0.265944511 -0.040331542 0.064253554 -0.009008419 0.997077584
1403637151588318976 0.303764224 -0.455111653 0.269622564 -0.040495720 0.064406611 -0.010850088 0.997042716
1403637151638319104 0.311635375 -0.471375346 0.272778779 -0.040882859 0.064445972 -0.012748954 0.997001886
1403637151688318976 0.317687541 -0.488277286 0.276899219 -0.040624667 0.064490482 -0.014579626 0.996984422
1403637151738319104 0.327079356 -0.498035073 0.283021271 -0.040784359 0.064455204 -0.015195645 0.996971071
1403637151788318976 0.333860606 -0.509185731 0.289889395 -0.041248504 0.064239591 -0.015998637 0.996953309
1403637151838319104 0.340459615 -0.520601869 0.293710291 -0.041038573 0.064066604 -0.016733292 0.996961057
1403637151888318976 0.346862912 -0.533094227 0.298782647 -0.041473299 0.064520843 -0.018204382 0.996887982
1403637151938319104 0.354856730 -0.540373027 0.303936332 -0.041491549 0.064858072 -0.018777695 0.996854722
1403637151988318976 0.362932086 -0.550742567 0.314978898 -0.041934583 0.064135738 -0.018988939 0.996878862
1403637152038319104 0.369900078 -0.562247038 0.315531671 -0.042223755 0.063912816 -0.018406009 0.996891916
1403637152088318976 0.377832413 -0.573443115 0.324075162 -0.042586837 0.063307315 -0.017162051 0.996937275
1403637152138319104 0.384627193 -0.586933970 0.327437252 -0.043366887 0.062840857 -0.016431402 0.996945500
1403637152188318976 0.391461134 -0.600330353 0.332126677 -0.044295881 0.062847674 -0.015699515 0.996916056
1403637152238319104 0.398779362 -0.609780788 0.344093263 -0.044835173 0.062421739 -0.014307160 0.996939659
1403637152288318976 0.408991963 -0.620008409 0.348997086 -0.045694221 0.062100749 -0.014150251 0.996922910
1403637152338319104 0.413622320 -0.630364239 0.353987068 -0.046917774 0.062001221 -0.012706034 0.996891737
1403637152388318976 0.422592580 -0.637277901 0.360893458 -0.046449244 0.061897378 -0.013453661 0.996910334
1403637152438319104 0.432953477 -0.647388577 0.369093418 -0.047452446 0.061854623 -0.013911105 0.996859431
1403637152488318976 0.442127824 -0.652282298 0.377845883 -0.047877911 0.061904002 -0.014699594 0.996824741
1403637152538319104 0.451411545 -0.654797792 0.387624174 -0.047515512 0.061575528 -0.014529022 0.996864915
1403637152588318976 0.461292446 -0.654070139 0.399308890 -0.047765445 0.061906643 -0.014857155 0.996827602
1403637152638319104 0.469687790 -0.654543519 0.412023485 -0.046727419 0.061990641 -0.015288865 0.996865094
1403637152688318976 0.480294555 -0.656800270 0.421767354 -0.046229824 0.062114384 -0.015302707 0.996880352
1403637152738319104 0.492106497 -0.657640517 0.432930380 -0.044132158 0.061774604 -0.014544828 0.997007847
1403637152788318976 0.500053287 -0.660078228 0.447704345 -0.041461576 0.060773876 -0.012124546 0.997216403
1403637152838319104 0.512162864 -0.664673269 0.456738859 -0.039015733 0.060541585 -0.011389298 0.997337818
1403637152888318976 0.523547649 -0.669274926 0.469512880 -0.036588993 0.060238354 -0.011229640 0.997449994
1403637152938319104 0.532341540 -0.675188661 0.480599850 -0.034582537 0.060270749 -0.012729806 0.997501612
1403637152988318976 0.544545054 -0.689293623 0.485307604 -0.034788299 0.060317520 -0.013780354 0.997477651
1403637153038319104 0.553378344 -0.695459008 0.497765422 -0.033897802 0.060429104 -0.014427375 0.997492433
1403637153088318976 0.566589236 -0.707885444 0.504958928 -0.035012331 0.061071813 -0.015420523 0.997399926
1403637153138319104 0.580008984 -0.715089023 0.512670457 -0.035895642 0.061211586 -0.016214401 0.997347355
1403637153188318976 0.590177417 -0.722294688 0.521160483 -0.037403505 0.061597615 -0.016446641 0.997264385
1403637153238319104 0.603134871 -0.725227296 0.536134243 -0.038302045 0.062206436 -0.017932985 0.997166872
1403637153288318976 0.614216268 -0.728129387 0.543298364 -0.038756438 0.062584192 -0.018787161 0.997109950
1403637153338319104 0.624285161 -0.730058610 0.553433597 -0.038567539 0.063069344 -0.019732095 0.997068405
1403637153388318976 0.635725737 -0.736630082 0.559549809 -0.039824206 0.063739195 -0.021281878 0.996944547
1403637153438319104 0.648661494 -0.738858879 0.564552784 -0.040796828 0.063707389 -0.021570854 0.996901035
1403637153488318976 0.658406198 -0.743494630 0.577203214 -0.042488996 0.064190648 -0.022372782 0.996781647
1403637153538319104 0.672463238 -0.752537668 0.583539605 -0.045301333 0.064651527 -0.023196818 0.996609211
1403637153588318976 0.680958748 -0.756436825 0.594531238 -0.046119764 0.064278215 -0.021417445 0.996635616
1403637153638319104 0.693291247 -0.772994339 0.596363544 -0.047421612 0.064481787 -0.022946499 0.996527374
1403637153688318976 0.703113556 -0.785498917 0.604398072 -0.046091497 0.064101063 -0.022729643 0.996619284
1403637153738319104 0.715325892 -0.798107088 0.608897746 -0.045030303 0.064259708 -0.022978062 0.996651888
1403637153788318976 0.720574737 -0.811358213 0.622306824 -0.042272903 0.064604469 -0.023195684 0.996745348
1403637153838319104 0.728757441 -0.820866048 0.630539596 -0.040371027 0.064118281 -0.021579824 0.996891856
1403637153888318976 0.738384902 -0.832047343 0.637567043 -0.039522484 0.064420432 -0.022166999 0.996893466
1403637153938319104 0.750141382 -0.838796735 0.644798636 -0.037724666 0.064233221 -0.022263423 0.996973097
1403637153988318976 0.757612586 -0.850220382 0.653823495 -0.037337426 0.064292006 -0.021754110 0.996995091
1403637154038319104 0.765116096 -0.851716638 0.663898051 -0.037708510 0.064281404 -0.021556575 0.996986091
1403637154088318976 0.773920596 -0.854632795 0.672032773 -0.039709739 0.063656986 -0.019585134 0.996989131
1403637154138319104 0.782063365 -0.857584417 0.683596551 -0.044219531 0.062306479 -0.015369131 0.996958554
1403637154188318976 0.790477157 -0.854964137 0.695498228 -0.050125588 0.060030181 -0.006698997 0.996914744
1403637154238319104 0.797563195 -0.852129519 0.707614481 -0.054067008 0.057880476 0.001863612 0.996856630
1403637154288318976 0.806423664 -0.848389804 0.721865833 -0.057730608 0.056267053 0.008441687 0.996709585
1403637154338319104 0.817096114 -0.845564902 0.734752834 -0.059534140 0.055619162 0.011121063 0.996613562
1403637154388318976 0.833371341 -0.842414081 0.744132280 -0.059066489 0.056546036 0.008619825 0.996613920
1403637154438319104 0.845723391 -0.838594675 0.761942148 -0.055196904 0.058388624 0.004311664 0.996757448
1403637154488318976 0.860868990 -0.834465384 0.775282681 -0.050419033 0.060037352 -0.000049827 0.996922016
1403637154538319104 0.881181955 -0.828383863 0.789802194 -0.047263879 0.061775457 -0.003666938 0.996963620
1403637154588318976 0.896933436 -0.823067844 0.805126548 -0.046281550 0.064124644 -0.008129512 0.996834934
1403637154638319104 0.917474270 -0.821285307 0.819262445 -0.048110683 0.067012012 -0.013561033 0.996499300
1403637154688318976 0.935394287 -0.817868173 0.834264994 -0.052362747 0.070351213 -0.018820642 0.995969176
1403637154738319104 0.952673912 -0.816029668 0.851182461 -0.056412417 0.074270837 -0.021964643 0.995398939
1403637154788318976 0.972596586 -0.811904788 0.867505968 -0.059553534 0.079660103 -0.022039719 0.994797409
1403637154838319104 0.989112020 -0.813239574 0.887997329 -0.062974162 0.085957401 -0.020390006 0.994097471
1403637154888318976 1.009939551 -0.814076424 0.901000381 -0.064043671 0.091137104 -0.017424639 0.993624091
1403637154938319104 1.026250243 -0.809961379 0.919745564 -0.066631824 0.096186735 -0.015240232 0.993013620
1403637154988318976 1.046633720 -0.804996371 0.935117424 -0.064898521 0.100430913 -0.010920194 0.992765069
1403637155038319104 1.054419875 -0.824472904 0.966705739 -0.064721175 0.106755525 -0.010220284 0.992123961
1403637155088318976 1.071686864 -0.834941268 0.988300622 -0.062681943 0.112897575 -0.006381743 0.991606951
1403637155138319104 1.089273334 -0.849476218 1.011038423 -0.056688953 0.119891860 -0.004067502 0.991158783
1403637155188318976 1.100565195 -0.861150026 1.031321764 -0.052558087 0.125733376 -0.000646433 0.990670621
1403637155238319104 1.114654660 -0.877133846 1.060245991 -0.048512120 0.130706117 0.000095636 0.990233541
1403637155288318976 1.131289959 -0.893470526 1.082519174 -0.044997428 0.133731917 0.001384230 0.989994526
1403637155338319104 1.148253322 -0.912011981 1.104773760 -0.040824428 0.136989489 0.002206060 0.989728451
1403637155388318976 1.163734913 -0.929356337 1.123842239 -0.036963940 0.141388685 0.004626382 0.989253044
1403637155438319104 1.178028226 -0.950690150 1.150738835 -0.034617338 0.147758603 0.006561760 0.988395631
1403637155488318976 1.190460443 -0.955927908 1.166695714 -0.030823676 0.155218482 0.010028856 0.987348258
1403637155538319104 1.206891179 -0.977262139 1.201811075 -0.029919550 0.162007973 0.013468920 0.986243784
1403637155588318976 1.222468972 -0.985942066 1.221833587 -0.028870145 0.167510942 0.018344546 0.985276639
1403637155638319104 1.239093304 -0.992632270 1.245282412 -0.027909745 0.171851605 0.024288381 0.984427810
1403637155688318976 1.252673745 -1.000408530 1.274156809 -0.028568482 0.176467031 0.029215723 0.983458042
1403637155738319104 1.270242929 -1.000054955 1.295005679 -0.027408449 0.181981236 0.033959359 0.982333124
1403637155788318976 1.284174919 -1.001351476 1.318416595 -0.027349018 0.188412651 0.039553095 0.980911970
1403637155838319104 1.305241466 -1.001002550 1.333776951 -0.025985839 0.195947453 0.044869170 0.979242623
1403637155888318976 1.324158669 -1.003128529 1.355699658 -0.028578835 0.205794275 0.049154088 0.976942122
1403637155938319104 1.342997313 -1.001071334 1.380389929 -0.031284243 0.216454685 0.052421585 0.974382162
1403637155988318976 1.361862183 -0.996031582 1.395149112 -0.031267926 0.227650195 0.056381453 0.971606314
1403637156038319104 1.382367969 -0.996015668 1.424868822 -0.029351607 0.239045545 0.060916938 0.968651056
1403637156088318976 1.407886505 -0.992524087 1.440549135 -0.026675060 0.249617234 0.066546589 0.965686917
1403637156138319104 1.427963734 -0.988743007 1.459344864 -0.023639854 0.261141598 0.071455993 0.962361813
1403637156188318976 1.461748838 -0.988473952 1.474583268 -0.021576758 0.272348970 0.077402994 0.958837450
1403637156238319104 1.487354755 -0.985661983 1.485951662 -0.019264711 0.284218132 0.083160669 0.954951942
1403637156288318976 1.515138626 -0.988350868 1.505195975 -0.018551460 0.296861976 0.087321125 0.950738549
1403637156338319104 1.537062049 -0.990700662 1.521446586 -0.017601909 0.309761852 0.093246609 0.946067035
1403637156388318976 1.577793717 -0.973738372 1.526089311 -0.016048849 0.322130084 0.098207928 0.941450953
1403637156438319104 1.607972622 -0.968384743 1.540538311 -0.015644528 0.335180402 0.102672085 0.936412156
1403637156488318976 1.631855369 -0.959649682 1.556586146 -0.014180473 0.348696560 0.106488757 0.931058407
1403637156538319104 1.658703089 -0.960671544 1.562872410 -0.012484934 0.361795336 0.109484360 0.925722122
1403637156588318976 1.693001509 -0.951678813 1.573547482 -0.011890763 0.374371648 0.112607270 0.920339108
1403637156638319104 1.729455113 -0.947641194 1.570055723 -0.010603763 0.387026221 0.115121923 0.914792418
1403637156688318976 1.756577373 -0.934404850 1.587471604 -0.009960185 0.400286198 0.117557913 0.908763945
1403637156738319104 1.800684452 -0.927867413 1.588428736 -0.009512955 0.412148237 0.118263580 0.903358757
1403637156788318976 1.832058191 -0.920221329 1.584348083 -0.012508366 0.422266454 0.118972361 0.898543358
1403637156838319104 1.870561838 -0.900340438 1.587221622 -0.016561346 0.431373179 0.118421718 0.894214272
1403637156888318976 1.921725869 -0.887625217 1.582897902 -0.020889446 0.437515229 0.119407274 0.891002774
1403637156938319104 1.960783124 -0.868426204 1.586680293 -0.025112715 0.443424672 0.117576793 0.888211489
1403637156988318976 1.989656448 -0.850938201 1.596372724 -0.029486137 0.448145986 0.117406532 0.885726511
1403637157038319104 2.023657322 -0.831077218 1.596999884 -0.032354299 0.450573683 0.118670382 0.884225011
1403637157088318976 2.058914423 -0.814977229 1.602420568 -0.034163855 0.452029854 0.120394759 0.883180022
1403637157138319104 2.091380835 -0.797686517 1.601374030 -0.034496866 0.452350795 0.122553937 0.882705688
1403637157188318976 2.132282257 -0.782797813 1.601221561 -0.034329921 0.451775223 0.124822341 0.882689059
1403637157238319104 2.179101467 -0.761093557 1.596496701 -0.033028498 0.450460434 0.126596957 0.883157790
1403637157288318976 2.218194008 -0.748689294 1.596687198 -0.031857371 0.449239641 0.128354773 0.883568823
1403637157338319104 2.254861116 -0.736546040 1.602636695 -0.030105172 0.448040098 0.129534662 0.884067059
1403637157388318976 2.286398411 -0.730136395 1.597484112 -0.028213704 0.445782781 0.133389041 0.884697199
1403637157438319104 2.333846092 -0.722657800 1.595908403 -0.026062477 0.443093926 0.137353346 0.885506928
1403637157488318976 2.368137836 -0.724009752 1.593728542 -0.024809269 0.440651447 0.140351743 0.886291265
1403637157538319104 2.428234577 -0.714460731 1.584401965 -0.023232983 0.437614620 0.142766163 0.887452245
1403637157588318976 2.466336489 -0.718221545 1.583869338 -0.022465434 0.435979933 0.143810421 0.888107717
1403637157638319104 2.510097742 -0.715354323 1.574250460 -0.022591520 0.434496224 0.143669203 0.888854206
1403637157688318976 2.560534000 -0.719414175 1.563018918 -0.022411244 0.432925940 0.143867567 0.889592588
1403637157738319104 2.603028297 -0.725098372 1.560993314 -0.022668663 0.432104319 0.144086748 0.889949977
1403637157788318976 2.632898808 -0.732197583 1.556531668 -0.019821612 0.432989061 0.140986487 0.890084505
1403637157838319104 2.688627720 -0.734592438 1.533684731 -0.017470177 0.433422536 0.135909095 0.890712321
1403637157888318976 2.760316133 -0.723959088 1.516118288 -0.014749810 0.433010668 0.132326990 0.891500831
1403637157938319104 2.812963486 -0.734286487 1.503480315 -0.012867860 0.434721708 0.128287792 0.891287684
1403637157988318976 2.873515606 -0.741047382 1.480841637 -0.013285843 0.435679197 0.124629386 0.891333103
1403637158038319104 2.920841217 -0.734928250 1.463397980 -0.013369976 0.437410921 0.118655771 0.891298950
1403637158088318976 2.978975058 -0.729271650 1.444928408 -0.014105017 0.438803047 0.114034809 0.891206503
1403637158138319104 3.036799908 -0.736002624 1.432394743 -0.014163267 0.439424634 0.112432048 0.891102970
1403637158188318976 3.078316927 -0.735154688 1.409934282 -0.014522551 0.440222919 0.110437788 0.890952528
1403637158238319104 3.133358479 -0.740202308 1.388402462 -0.013408625 0.440725535 0.110023037 0.890772760
1403637158288318976 3.185221195 -0.740640879 1.364524841 -0.013715940 0.443010181 0.110141285 0.889619470
1403637158338319104 3.250446796 -0.745564222 1.331983805 -0.013502928 0.445375323 0.110861458 0.888351381
1403637158388318976 3.308585644 -0.742571831 1.317746162 -0.011947649 0.450220287 0.113126568 0.885641754
1403637158438319104 3.351039410 -0.746174455 1.297355175 -0.010776005 0.456748396 0.115545116 0.881994426
1403637158488318976 3.397176027 -0.754490554 1.268699884 -0.008330024 0.462939143 0.120405532 0.878134668
1403637158538319104 3.454697609 -0.747229695 1.235097528 -0.005350246 0.469564795 0.124895595 0.874003112
1403637158588318976 3.499064445 -0.748363376 1.217337608 -0.002510012 0.477416992 0.132483214 0.868628204
1403637158638319104 3.566340208 -0.748097301 1.179409504 -0.000277742 0.484549493 0.139173046 0.863621771
1403637158688318976 3.623022318 -0.739846706 1.155811548 0.001984344 0.493976653 0.143773496 0.857503593
1403637158738319104 3.669058800 -0.733129561 1.123276234 0.002515970 0.503993571 0.147732913 0.850975454
1403637158788318976 3.726659060 -0.714493692 1.092599630 0.002395399 0.512335598 0.150488868 0.845493734
1403637158838319104 3.783637524 -0.710905313 1.056179643 -0.001218826 0.519583881 0.154404417 0.840351403
1403637158888318976 3.813205719 -0.700133562 1.032767415 -0.002978122 0.526318669 0.156193674 0.835813046
1403637158938319104 3.872809649 -0.683351755 0.994403064 -0.007213877 0.531909287 0.154133707 0.832624316
1403637158988318976 3.924532652 -0.672641814 0.966686964 -0.011786300 0.537051022 0.152901307 0.829492927
1403637159038319104 3.976072788 -0.670733333 0.926144242 -0.015938688 0.540537059 0.152744517 0.827184856
1403637159088318976 4.019334793 -0.665372550 0.895244837 -0.017155821 0.543249667 0.152739897 0.825382352
1403637159138319104 4.068610191 -0.642366707 0.861154795 -0.015344633 0.544420004 0.152550921 0.824681520
1403637159188318976 4.115373611 -0.651307821 0.829708457 -0.013312254 0.544058204 0.157272190 0.824068487
1403637159238319104 4.176146507 -0.643619955 0.781874180 -0.010682537 0.542514086 0.160964385 0.824411809
1403637159288318976 4.224613667 -0.635681391 0.748303950 -0.008993424 0.541296065 0.163701892 0.824693501
1403637159338319104 4.279565811 -0.624023736 0.707905769 -0.007854658 0.539882779 0.165767312 0.825218797
1403637159388318976 4.326791763 -0.612339139 0.668810725 -0.007440389 0.538590908 0.166840881 0.825850248
1403637159438319104 4.374825954 -0.591584086 0.635450363 -0.007445890 0.538490176 0.165134922 0.826258659
1403637159488318976 4.428652287 -0.572415709 0.597311974 -0.006675687 0.537217438 0.164703026 0.827179432
1403637159538319104 4.479371071 -0.552095652 0.566501975 -0.009980581 0.538084507 0.160391018 0.827429891
1403637159588318976 4.522698402 -0.548689306 0.530100107 -0.014730644 0.538193703 0.158424750 0.827666640
1403637159638319104 4.586461544 -0.527282059 0.482325554 -0.018707562 0.537805855 0.154547080 0.828571081
1403637159688318976 4.641055584 -0.508629620 0.444514871 -0.020688305 0.537731051 0.151501834 0.829134762
1403637159738319104 4.697041512 -0.500517786 0.400038362 -0.023625081 0.537988901 0.148425430 0.829445422
1403637159788318976 4.746100426 -0.489258409 0.368033528 -0.023866970 0.538930833 0.146407396 0.829185605
1403637159838319104 4.796936035 -0.458888769 0.337917805 -0.021652618 0.540867925 0.144233078 0.828365743
1403637159888318976 4.851650238 -0.462484241 0.292828083 -0.024554389 0.543704212 0.143129677 0.826617599
1403637159938319104 4.910559654 -0.462752163 0.243031025 -0.025390010 0.547439575 0.147093356 0.823425055
1403637159988318976 4.963578224 -0.463098943 0.207933068 -0.027244370 0.554830909 0.148930281 0.818071008
1403637160038319104 5.026622772 -0.452055097 0.156483650 -0.024069520 0.560927391 0.151913404 0.813451588
1403637160088318976 5.072917938 -0.436091304 0.122980118 -0.018565284 0.569625795 0.154794961 0.806982219
1403637160138319104 5.138568878 -0.424399495 0.077894926 -0.013245236 0.577782989 0.158091098 0.800623894
1403637160188318976 5.201310158 -0.425276399 0.024003267 -0.011513636 0.586515725 0.161054581 0.793680131
1403637160238319104 5.265174866 -0.409998775 -0.015426636 -0.009864042 0.596960962 0.163770109 0.785314977
1403637160288318976 5.312113762 -0.392113209 -0.055278420 -0.007892783 0.608210444 0.166637287 0.776047528
1403637160338319104 5.371261597 -0.376505494 -0.097175598 -0.007759056 0.620021045 0.168728814 0.766188145
1403637160388318976 5.424766541 -0.358251572 -0.135450363 -0.006318609 0.631692231 0.173747227 0.755471230
1403637160438319104 5.479804516 -0.334803700 -0.181899250 -0.007074661 0.643436372 0.176455408 0.744850993
1403637160488318976 5.520610809 -0.314405799 -0.221991658 -0.008780427 0.656317472 0.178636670 0.732979715
1403637160538319104 5.581919193 -0.290710449 -0.246881485 -0.011907757 0.670337260 0.181925595 0.719311655
1403637160588318976 5.642161846 -0.266547561 -0.301296681 -0.013765762 0.681191385 0.185032234 0.708203316
1403637160638319104 5.694233894 -0.249149919 -0.321900666 -0.016874656 0.693894446 0.187611625 0.695001900
1403637160688318976 5.746888638 -0.225738406 -0.376952410 -0.018913276 0.701826155 0.192126527 0.685689211
1403637160738319104 5.800705910 -0.200407982 -0.408512503 -0.021314071 0.709544539 0.196321815 0.676424384
1403637160788318976 5.851550102 -0.179225087 -0.447139859 -0.024264541 0.715484142 0.198888868 0.669280887
1403637160838319104 5.902580738 -0.163325191 -0.482501924 -0.025530085 0.720142007 0.201115131 0.663548350
1403637160888318976 5.951242924 -0.150032759 -0.509871840 -0.026025359 0.723943174 0.203717247 0.658580482
1403637160938319104 6.002272606 -0.132710576 -0.557807207 -0.026926344 0.725559056 0.207089394 0.655708015
1403637160988318976 6.057378292 -0.122389197 -0.591449201 -0.026138688 0.726748526 0.210902601 0.653202415
1403637161038319104 6.114773750 -0.125622749 -0.615455866 -0.025057297 0.727494001 0.215776041 0.650818944
1403637161088318976 6.165713310 -0.120541096 -0.658123136 -0.021088105 0.727140665 0.219474196 0.650117517
1403637161138319104 6.218389511 -0.119252443 -0.697859526 -0.015119997 0.726653874 0.222832873 0.649685323
1403637161188318976 6.272214890 -0.122497559 -0.741184890 -0.006345424 0.724992394 0.227798671 0.649964273
1403637161238319104 6.325567245 -0.124081373 -0.784702301 0.004585543 0.723886967 0.230481535 0.650265217
1403637161288318976 6.381404400 -0.134913206 -0.821402490 0.013026257 0.722465813 0.234367952 0.650342345
1403637161338319104 6.434831142 -0.139271498 -0.866349876 0.018605411 0.721293509 0.236054465 0.650897622
1403637161388318976 6.495321274 -0.153219461 -0.914619863 0.018199557 0.721590698 0.235012844 0.650956690
1403637161438319104 6.547549248 -0.164857268 -0.967010856 0.014136865 0.723337114 0.232086346 0.650168836
1403637161488318976 6.602283001 -0.173654437 -1.024499536 0.012285678 0.725434840 0.230432540 0.648455262
1403637161538319104 6.655212402 -0.180238485 -1.063690066 0.008752165 0.729072154 0.230006456 0.644572854
1403637161588318976 6.721633434 -0.187930346 -1.135475278 0.007072652 0.732246876 0.229901180 0.641022682
1403637161638319104 6.765231609 -0.193922281 -1.167816639 0.006639946 0.737735331 0.229225829 0.634947181
1403637161688318976 6.814572334 -0.194962025 -1.230350375 0.007891850 0.742026150 0.226896837 0.630755782
1403637161738319104 6.866175652 -0.195156813 -1.289510489 0.010335793 0.746830046 0.222781032 0.626503587
1403637161788318976 6.917132854 -0.191485882 -1.353517294 0.013090909 0.752041817 0.214699581 0.623029649
1403637161838319104 6.971259117 -0.184670687 -1.397709250 0.017370308 0.758561015 0.204935566 0.618292034
1403637161888318976 7.013523579 -0.209469199 -1.461087465 0.020161830 0.763361573 0.197932065 0.614569426
1403637161938319104 7.062623978 -0.204711080 -1.508930445 0.025531845 0.768519461 0.189122006 0.610703588
1403637161988318976 7.111224174 -0.199227333 -1.556547165 0.029626053 0.773042262 0.181348681 0.607157886
1403637162038319104 7.153660774 -0.203084826 -1.614595175 0.033087749 0.776001632 0.176043779 0.604760528
1403637162088318976 7.193584919 -0.199871778 -1.658519983 0.034714274 0.778510869 0.172864884 0.602356672
1403637162138319104 7.228086948 -0.187306762 -1.727440596 0.038364314 0.778605878 0.172720939 0.602053702
1403637162188318976 7.257664204 -0.182738423 -1.773853660 0.041408855 0.777931809 0.177092001 0.601453006
1403637162238319104 7.288353443 -0.164546132 -1.824478269 0.044016812 0.776201010 0.183215380 0.601669908
1403637162288318976 7.314221382 -0.155800462 -1.874410152 0.045644488 0.774281144 0.189517453 0.602070153
1403637162338319104 7.341651917 -0.137638807 -1.922525167 0.045733340 0.772866011 0.194137171 0.602409661
1403637162388318976 7.364027023 -0.123255730 -1.971934915 0.047368295 0.770792902 0.200113043 0.602983654
1403637162438319104 7.377384663 -0.110016942 -2.020402908 0.048424426 0.767948866 0.207616329 0.603990972
1403637162488318976 7.395488262 -0.087383986 -2.077632904 0.042467065 0.765320957 0.215062350 0.605168223
1403637162538319104 7.409051895 -0.064571142 -2.131241560 0.034303728 0.764005482 0.219350234 0.605808794
1403637162588318976 7.423076630 -0.050875425 -2.181979418 0.028884806 0.763989449 0.219906464 0.605910003
1403637162638319104 7.434385777 -0.039923429 -2.229398012 0.025896341 0.766078532 0.214832872 0.605227113
1403637162688318976 7.443167686 -0.029412270 -2.295585155 0.030765396 0.767767131 0.208217129 0.605171621
1403637162738319104 7.451501846 -0.033452153 -2.361268520 0.039845642 0.770660281 0.202739224 0.602819920
1403637162788318976 7.455757618 -0.007249355 -2.402659416 0.048572745 0.776147366 0.195848316 0.597393811
1403637162838319104 7.460466862 0.008780003 -2.464786768 0.050574131 0.781455040 0.193795502 0.590942919
1403637162888318976 7.462540150 0.022321105 -2.529628038 0.051711921 0.787698627 0.192642778 0.582876921
1403637162938319104 7.459249496 0.042083025 -2.590168953 0.050231412 0.795413315 0.191230550 0.572909594
1403637162988318976 7.453575134 0.062286735 -2.651078939 0.047697961 0.803376675 0.191116273 0.561947703
1403637163038319104 7.441177368 0.087150216 -2.703782797 0.044570632 0.812444031 0.190674722 0.549173236
1403637163088318976 7.433278084 0.111714959 -2.769967556 0.042294998 0.821313858 0.192171603 0.535466790
1403637163138319104 7.416437626 0.135028362 -2.825699329 0.038734876 0.831371725 0.191899672 0.520091474
1403637163188318976 7.403660774 0.160406351 -2.890645027 0.037190501 0.840574563 0.194451183 0.504222274
1403637163238319104 7.381819725 0.177278757 -2.938051224 0.035771515 0.850669980 0.195892081 0.486525744
1403637163288318976 7.366128445 0.207465887 -3.018492222 0.034296405 0.858037174 0.197760388 0.472743899
1403637163338319104 7.341018677 0.236421108 -3.057314634 0.036132276 0.866920471 0.199841276 0.455199808
1403637163388318976 7.313393116 0.266545534 -3.110553503 0.038784686 0.873305738 0.203854144 0.440767884
1403637163438319104 7.283237934 0.283685207 -3.150525093 0.041565642 0.879297793 0.210570455 0.425167948
1403637163488318976 7.262922287 0.322911978 -3.203633547 0.045107383 0.883413196 0.216480479 0.413137496
1403637163538319104 7.229165554 0.351035118 -3.239189863 0.047167122 0.887035966 0.224297568 0.400790542
1403637163588318976 7.194126129 0.374371290 -3.277291775 0.049225558 0.888706267 0.233887672 0.391247451
1403637163638319104 7.157809734 0.395139217 -3.320374966 0.048657961 0.888994813 0.244920537 0.383841842
1403637163688318976 7.118552208 0.413687706 -3.372296810 0.050021589 0.888592362 0.254494458 0.378330499
1403637163738319104 7.085545540 0.427521229 -3.416422129 0.051355895 0.887846112 0.264635801 0.372907221
1403637163788318976 7.043069839 0.444590330 -3.457635403 0.051878244 0.888086855 0.269711465 0.368600249
1403637163838319104 6.996900558 0.455746889 -3.501940012 0.054983586 0.887131155 0.275473744 0.366182148
1403637163888318976 6.958212852 0.472897291 -3.544579506 0.059843477 0.887162805 0.278037697 0.363394976
1403637163938319104 6.900481701 0.482864380 -3.604776382 0.064231388 0.886444986 0.279011756 0.363651067
1403637163988318976 6.856225014 0.492237091 -3.650863647 0.067330293 0.887655079 0.277483582 0.361300409
1403637164038319104 6.805646896 0.491256475 -3.704383850 0.067720897 0.888007641 0.277290344 0.360508472
1403637164088318976 6.753037453 0.498489141 -3.765259027 0.068104565 0.888772190 0.274260700 0.360869467
1403637164138319104 6.695816040 0.509381294 -3.818552017 0.068134949 0.890048265 0.269855946 0.361039460
1403637164188318976 6.638303757 0.512111902 -3.887073040 0.066390492 0.890483797 0.266915858 0.362473160
1403637164238319104 6.575099468 0.510692358 -3.948729992 0.062503591 0.891023040 0.264794379 0.363393933
1403637164288318976 6.508238792 0.516172171 -4.010928154 0.056016605 0.892248690 0.259767205 0.365069121
1403637164338319104 6.444266319 0.518606901 -4.080517769 0.049276374 0.892171085 0.258767307 0.366936058
1403637164388318976 6.375141144 0.524137259 -4.136120796 0.045481477 0.892304957 0.257496327 0.367993057
1403637164438319104 6.303318024 0.529878378 -4.200843334 0.041677941 0.890897334 0.259448826 0.370474309
1403637164488318976 6.233573914 0.540200949 -4.257218838 0.042901579 0.889418244 0.261594653 0.372374684
1403637164538319104 6.168302536 0.553063154 -4.326236725 0.047633372 0.887194514 0.264299423 0.375183642
1403637164588318976 6.099899769 0.558417320 -4.382107735 0.050853305 0.885532737 0.267295986 0.376561493
1403637164638319104 6.016331673 0.572710514 -4.465709686 0.053575382 0.882697046 0.270456851 0.380563706
1403637164688318976 5.947679520 0.588425875 -4.524316788 0.051376112 0.882423401 0.270331502 0.381589204
1403637164738319104 5.874567986 0.613657713 -4.596115112 0.045713332 0.883190930 0.265947342 0.383609325
1403637164788318976 5.800539494 0.631726980 -4.663835526 0.039164808 0.885553539 0.259776086 0.383115411
1403637164838319104 5.730400562 0.654148579 -4.730347157 0.034606449 0.888302088 0.254042059 0.381030738
1403637164888318976 5.655711174 0.675977707 -4.798619747 0.029840143 0.891298652 0.249615461 0.377343923
1403637164938319104 5.579493523 0.698882580 -4.870860577 0.027055591 0.893755317 0.247561753 0.373071879
1403637164988318976 5.509880066 0.723831177 -4.942259312 0.025189897 0.896394908 0.246840283 0.367303044
1403637165038319104 5.427832127 0.755090237 -5.024711609 0.025317673 0.898454845 0.246565491 0.362413168
1403637165088318976 5.353362560 0.766807556 -5.077476025 0.024707047 0.902457714 0.246037751 0.352739275
1403637165138319104 5.273903370 0.794972897 -5.152376652 0.026671374 0.906355560 0.242784902 0.344766080
1403637165188318976 5.195148468 0.820753574 -5.207501888 0.025562793 0.911345780 0.240800664 0.332882077
1403637165238319104 5.123602390 0.853513718 -5.271059990 0.025821498 0.915679276 0.240497917 0.320975780
1403637165288318976 5.045730591 0.878808737 -5.335419655 0.023875952 0.918963492 0.243391037 0.309349060
1403637165338319104 4.965220451 0.896708250 -5.394042969 0.021863863 0.921094656 0.250197679 0.297502369
1403637165388318976 4.891966343 0.919925213 -5.456863880 0.017981330 0.922723889 0.256474644 0.287189901
1403637165438319104 4.812400818 0.935446978 -5.517759323 0.015920451 0.923380554 0.263779283 0.278451711
1403637165488318976 4.734637260 0.955133677 -5.576796532 0.015830215 0.924364328 0.268219262 0.270847738
1403637165538319104 4.652463913 0.968161106 -5.635059357 0.013288809 0.925625205 0.270862103 0.263960481
1403637165588318976 4.578061104 0.982009411 -5.690650940 0.011443416 0.926762283 0.273498386 0.257253468
1403637165638319104 4.503051758 0.994186163 -5.747100353 0.004475025 0.928574383 0.273032069 0.251362443
1403637165688318976 4.424310684 1.007369757 -5.805071831 -0.002329108 0.930015683 0.272170573 0.246958688
1403637165738319104 4.361701488 1.018827200 -5.865717888 -0.010314235 0.931364179 0.271191180 0.242713109
1403637165788318976 4.283214569 1.030749083 -5.917274952 -0.017898731 0.932462454 0.269613832 0.239795297
1403637165838319104 4.220652103 1.043587446 -5.974238396 -0.026091291 0.933451355 0.267890483 0.237112775
1403637165888318976 4.164906502 1.061496973 -6.021946907 -0.032420494 0.934018731 0.265904248 0.236332044
1403637165938319104 4.091473579 1.071772814 -6.074369431 -0.038018782 0.933744729 0.264509171 0.238139182
1403637165988318976 4.032489777 1.085566521 -6.118319511 -0.044551834 0.933142245 0.263102591 0.240910277
1403637166038319104 3.973039150 1.106815338 -6.168684483 -0.048632119 0.932236850 0.260836333 0.246035948
1403637166088318976 3.918983221 1.132395744 -6.213762283 -0.053949282 0.931221485 0.258793861 0.250881851
1403637166138319104 3.867234468 1.155975580 -6.255504131 -0.056176692 0.930456579 0.257047504 0.254992843
1403637166188318976 3.810589552 1.183404446 -6.296299458 -0.058099363 0.929354727 0.255872905 0.259717673
1403637166238319104 3.776582241 1.211925983 -6.330520153 -0.056916334 0.929417551 0.252768278 0.262776971
1403637166288318976 3.735800266 1.239294052 -6.364651680 -0.052121703 0.929772437 0.248294711 0.266751319
1403637166338319104 3.698026419 1.264459372 -6.401958466 -0.046290137 0.931562424 0.237374485 0.271481097
1403637166388318976 3.658869028 1.288700819 -6.432040691 -0.037153494 0.934163749 0.221795619 0.277063936
1403637166438319104 3.632326126 1.307245851 -6.456389427 -0.028163336 0.935878277 0.209110916 0.282154918
1403637166488318976 3.601080894 1.326179981 -6.486150265 -0.025133833 0.935970008 0.201478601 0.287636489
1403637166538319104 3.572015524 1.344766498 -6.505729198 -0.022056149 0.935333312 0.198799893 0.291793972
1403637166588318976 3.542783260 1.360392094 -6.520816803 -0.023680249 0.933415711 0.202086151 0.295525968
1403637166638319104 3.511621237 1.373275042 -6.537445545 -0.027336704 0.930211663 0.211460248 0.298736542
1403637166688318976 3.477389574 1.391015649 -6.543920517 -0.032479417 0.926106334 0.224499226 0.301450163
1403637166738319104 3.461296320 1.395460367 -6.553548336 -0.041838024 0.922969759 0.234090045 0.302619010
1403637166788318976 3.441317558 1.411652684 -6.554101944 -0.050120033 0.920686066 0.239558131 0.304034650
1403637166838319104 3.405137539 1.422823429 -6.563546181 -0.059354305 0.918719292 0.241398424 0.306852967
1403637166888318976 3.388551712 1.440794349 -6.566768646 -0.068938345 0.918503642 0.237764254 0.308328956
1403637166938319104 3.373167276 1.450973034 -6.567567348 -0.078255281 0.918587089 0.232732579 0.309692472
1403637166988318976 3.364072323 1.462692738 -6.559756279 -0.084611885 0.920068860 0.224189803 0.309924245
1403637167038319104 3.350062847 1.472432613 -6.555334568 -0.091103852 0.920955777 0.215638041 0.311513782
1403637167088318976 3.347444534 1.474688292 -6.542565346 -0.096761025 0.921929777 0.207480803 0.312465191
1403637167138319104 3.349449873 1.479792714 -6.528228760 -0.101506494 0.923121214 0.198931798 0.313001215
1403637167188318976 3.351449251 1.477047205 -6.506218433 -0.104534321 0.924293339 0.191007763 0.313481122
1403637167238319104 3.363257885 1.473282456 -6.485311508 -0.107559048 0.924954176 0.185419634 0.313863546
1403637167288318976 3.374541044 1.449006081 -6.458054543 -0.108772278 0.924959123 0.184913203 0.313729614
1403637167338319104 3.396076202 1.442256689 -6.423832893 -0.107744053 0.925184667 0.186291575 0.312601984
1403637167388318976 3.414842129 1.428621769 -6.381224632 -0.104879782 0.924519122 0.191800371 0.312213510
1403637167438319104 3.445600986 1.417611480 -6.342023849 -0.096777700 0.922882557 0.202664688 0.312808096
1403637167488318976 3.474176168 1.407919168 -6.291603565 -0.081291035 0.921362460 0.214011684 0.314136893
1403637167538319104 3.492560625 1.388449430 -6.230205059 -0.063975103 0.919210434 0.226541549 0.315655351
1403637167588318976 3.544315815 1.365356565 -6.178767681 -0.047860511 0.916948020 0.238087043 0.316591740
1403637167638319104 3.578633785 1.362161994 -6.126646042 -0.030887499 0.915087640 0.245662734 0.318292916
1403637167688318976 3.618337631 1.349269152 -6.068741798 -0.020224318 0.913045943 0.251343578 0.320568949
1403637167738319104 3.657435417 1.340593457 -6.013572216 -0.013631000 0.910660863 0.256042808 0.323964566
1403637167788318976 3.696528196 1.327347875 -5.953977108 -0.011004032 0.907578230 0.261100739 0.328644216
1403637167838319104 3.734632015 1.325633407 -5.893998146 -0.009941539 0.904346287 0.264925659 0.334474832
1403637167888318976 3.776443481 1.315413952 -5.835795879 -0.012122395 0.900754213 0.269504219 0.340385526
1403637167938319104 3.817137718 1.310992241 -5.779543877 -0.014993504 0.898189962 0.271610260 0.345337391
1403637167988318976 3.843111992 1.301440239 -5.728687286 -0.021522185 0.896084547 0.269928515 0.351721376
1403637168038319104 3.900915384 1.290373564 -5.672806740 -0.027411096 0.895312250 0.267645001 0.355008185
1403637168088318976 3.933208942 1.274554491 -5.620138168 -0.029026814 0.893565655 0.266493589 0.360109806
1403637168138319104 3.987193584 1.267257929 -5.567156315 -0.025538746 0.891679168 0.268956423 0.363205880
1403637168188318976 4.031009197 1.250530720 -5.516921043 -0.023826586 0.890125453 0.270079136 0.366287231
1403637168238319104 4.078596592 1.244614601 -5.463650703 -0.021795847 0.890027821 0.267354369 0.368642300
1403637168288318976 4.128582001 1.253286839 -5.404400349 -0.019918695 0.890837669 0.262754142 0.370096892
1403637168338319104 4.177954197 1.257191896 -5.351123810 -0.019546980 0.892094493 0.256437153 0.371517658
1403637168388318976 4.225957394 1.266067028 -5.297515869 -0.017654408 0.893997312 0.248337805 0.372539133
1403637168438319104 4.273337364 1.270781159 -5.242646694 -0.016987421 0.895581543 0.240853295 0.373677433
1403637168488318976 4.315237999 1.273869038 -5.189999580 -0.011794731 0.896511316 0.235284418 0.375192642
1403637168538319104 4.370939255 1.289186954 -5.127650738 -0.008632502 0.897311211 0.232506305 0.375098497
1403637168588318976 4.424720764 1.297354341 -5.062644958 -0.006183873 0.896573603 0.235282198 0.375179708
1403637168638319104 4.461667061 1.315158844 -5.004590988 -0.004613841 0.895488441 0.237936080 0.376119167
1403637168688318976 4.521875381 1.317411661 -4.957136154 -0.007947140 0.894276500 0.241608635 0.376605392
1403637168738319104 4.572891712 1.328816414 -4.888596535 -0.009494381 0.894216180 0.243452743 0.375523627
1403637168788318976 4.617652893 1.315607667 -4.842327118 -0.010110033 0.892942190 0.247485489 0.375902951
1403637168838319104 4.665924549 1.309423327 -4.793365002 -0.013293888 0.892396390 0.249908507 0.375496656
1403637168888318976 4.707237244 1.321294904 -4.727376938 -0.014929447 0.893022358 0.248413622 0.374938548
1403637168938319104 4.763532162 1.321974277 -4.664720058 -0.019328697 0.893754542 0.247872248 0.373347789
1403637168988318976 4.812173367 1.313671947 -4.614688873 -0.022334510 0.893672943 0.248484612 0.372968167
1403637169038319104 4.859570026 1.315900922 -4.556622505 -0.026280403 0.894400716 0.246703386 0.372148007
1403637169088318976 4.911800385 1.322585464 -4.499419212 -0.031163216 0.894766629 0.244605422 0.372276425
1403637169138319104 4.959149361 1.317888856 -4.446199417 -0.032754552 0.894340277 0.242519766 0.374521971
1403637169188318976 5.001332760 1.316380382 -4.385869026 -0.033507064 0.893260241 0.239297658 0.379077882
1403637169238319104 5.067745209 1.319379091 -4.324950695 -0.033313729 0.891883492 0.235201046 0.384856403
1403637169288318976 5.128952026 1.307739377 -4.252616882 -0.032851987 0.890039563 0.231217310 0.391521156
1403637169338319104 5.174499512 1.298130512 -4.199823380 -0.030022006 0.886033952 0.227958366 0.402588367
1403637169388318976 5.233376503 1.286703706 -4.141064644 -0.028655265 0.881913900 0.224781677 0.413376272
1403637169438319104 5.293342590 1.276124597 -4.059893131 -0.028259639 0.878139138 0.219480768 0.424147606
1403637169488318976 5.348239422 1.252248764 -4.017743587 -0.027442543 0.871443272 0.216739833 0.439155251
1403637169538319104 5.405577183 1.223791838 -3.943279505 -0.028513122 0.866281450 0.211199701 0.451816440
1403637169588318976 5.460481644 1.213643074 -3.877342224 -0.028959706 0.859788477 0.203689322 0.467371017
1403637169638319104 5.528560638 1.184472561 -3.797368288 -0.032632031 0.853901386 0.195068702 0.481389374
1403637169688318976 5.581274986 1.158542275 -3.737785339 -0.032344468 0.845554054 0.190046206 0.497870088
1403637169738319104 5.639687538 1.125570893 -3.679195881 -0.032954857 0.835907221 0.187193274 0.514909565
1403637169788318976 5.690228462 1.125105500 -3.596223593 -0.031484019 0.827958286 0.180769548 0.529920936
1403637169838319104 5.742026806 1.093132138 -3.519703388 -0.032797337 0.819584310 0.176835239 0.543999195
1403637169888318976 5.786417007 1.084692478 -3.438085079 -0.035324510 0.812194645 0.169613823 0.557066500
1403637169938319104 5.842434883 1.065378070 -3.358346939 -0.036110595 0.805073857 0.165240601 0.568548739
1403637169988318976 5.907833099 1.038635015 -3.263432980 -0.039838567 0.798452973 0.159224361 0.579252422
1403637170038319104 5.950760841 1.025125027 -3.186874390 -0.040544562 0.790671825 0.155402556 0.590799630
1403637170088318976 6.010442734 1.003066778 -3.098531246 -0.042900600 0.783256948 0.153081611 0.601027608
1403637170138319104 6.054943085 0.991483569 -3.003511429 -0.042644545 0.775546610 0.147915050 0.612233698
1403637170188318976 6.102210999 0.972107947 -2.926623821 -0.041028291 0.766706347 0.144959345 0.624071181
1403637170238319104 6.152631760 0.960237265 -2.811248064 -0.042009726 0.760180712 0.139592752 0.633146405
1403637170288318976 6.198871613 0.939938903 -2.718042374 -0.043505836 0.751961052 0.135164574 0.643733084
1403637170338319104 6.242905617 0.941523790 -2.615434885 -0.040073223 0.743409157 0.129478395 0.654959798
1403637170388318976 6.289533615 0.928949296 -2.510475397 -0.032862186 0.733014762 0.128612727 0.667134345
1403637170438319104 6.329847813 0.920790911 -2.403328419 -0.022257667 0.722262323 0.127065778 0.679482162
1403637170488318976 6.371831894 0.912987530 -2.299270868 -0.010228690 0.710021853 0.125732049 0.692788422
1403637170538319104 6.407593727 0.901081562 -2.205340385 0.001759218 0.697116971 0.123299234 0.706273377
1403637170588318976 6.447824955 0.899249911 -2.092131376 0.013295732 0.685414493 0.118019320 0.718402147
1403637170638319104 6.471992016 0.873329639 -1.973904371 0.021214163 0.673699439 0.114859611 0.729716599
1403637170688318976 6.499521732 0.866596282 -1.862294197 0.030633282 0.661442578 0.109173790 0.741374671
1403637170738319104 6.523377419 0.848724604 -1.757740736 0.034214199 0.648964226 0.104252286 0.752865374
1403637170788318976 6.551651478 0.869681597 -1.666138291 0.039796844 0.633806705 0.100733079 0.765870869
1403637170838319104 6.560062408 0.885764003 -1.558582425 0.038396195 0.620472848 0.097545981 0.777189791
1403637170888318976 6.564253330 0.861987174 -1.438266277 0.035374444 0.606141269 0.096825033 0.788648427
1403637170938319104 6.571040630 0.861644983 -1.337267280 0.031656694 0.590618372 0.095081314 0.800704300
1403637170988318976 6.566016674 0.845604300 -1.241317630 0.026117088 0.575554132 0.094168037 0.811903775
1403637171038319104 6.572985649 0.827897310 -1.167775154 0.023178002 0.558050573 0.093946218 0.824145913
1403637171088318976 6.565715790 0.808507144 -1.076207638 0.021254644 0.541495502 0.095378645 0.835005224
1403637171138319104 6.559874535 0.798071027 -0.979808331 0.017591089 0.528275073 0.094044164 0.843665659
1403637171188318976 6.545070648 0.785614967 -0.881460428 0.016877780 0.517057538 0.092686534 0.850750148
1403637171238319104 6.549984932 0.775511146 -0.819521904 0.019084796 0.504098177 0.092475034 0.858469069
1403637171288318976 6.530278206 0.748359680 -0.716618299 0.020185098 0.497654289 0.089060888 0.862554848
1403637171338319104 6.516221046 0.722071290 -0.639284611 0.020331632 0.491148174 0.084704220 0.866709471
1403637171388318976 6.511038780 0.697112441 -0.581213474 0.017918093 0.484908462 0.077978522 0.870897293
1403637171438319104 6.474548340 0.682800829 -0.484341383 0.017096251 0.485260427 0.070723481 0.871337056
1403637171488318976 6.444882393 0.657907128 -0.403726578 0.014833701 0.483984917 0.066802658 0.872396708
1403637171538319104 6.416824818 0.633437753 -0.336220264 0.012619418 0.482423782 0.064091474 0.873498917
1403637171588318976 6.387573242 0.613585889 -0.269870996 0.010813577 0.481555700 0.061690159 0.874174714
1403637171638319104 6.353128910 0.594731629 -0.186030388 0.009314516 0.483772010 0.057477959 0.873254955
1403637171688318976 6.318253040 0.577746868 -0.121840000 0.008542743 0.484314680 0.055362858 0.873098671
1403637171738319104 6.280631065 0.555348039 -0.057430983 0.007932382 0.485666096 0.053921219 0.872443676
1403637171788318976 6.239985466 0.541916847 0.011163712 0.007816676 0.488044709 0.051659491 0.871253431
1403637171838319104 6.194692135 0.524739385 0.076332092 0.007225737 0.490775377 0.048912760 0.869882107
1403637171888318976 6.146554947 0.516733110 0.147340775 0.008608500 0.493283361 0.047796518 0.868511856
1403637171938319104 6.088028431 0.491546094 0.219581842 0.007469296 0.496782035 0.048061125 0.866511345
1403637171988318976 6.042241096 0.493304312 0.281212330 0.010157507 0.497683853 0.046890020 0.866030574
1403637172038319104 5.986749172 0.484114617 0.350272179 0.010397552 0.500164330 0.046295967 0.864629507
1403637172088318976 5.925290108 0.472854912 0.415111780 0.011154572 0.501979530 0.046548896 0.863553882
1403637172138319104 5.862161160 0.462522715 0.476873398 0.011408448 0.502337575 0.050341293 0.863129556
1403637172188318976 5.794003010 0.462348998 0.547327042 0.014044207 0.501657248 0.058850344 0.862948060
1403637172238319104 5.731432915 0.460974187 0.600302458 0.013292416 0.498193175 0.071303830 0.864026964
1403637172288318976 5.651984692 0.445048332 0.661065102 0.010649886 0.495482743 0.085995026 0.864284873
1403637172338319104 5.574216366 0.440447420 0.727258205 0.010555429 0.493798941 0.098146304 0.863955140
1403637172388318976 5.494652748 0.430123448 0.790978312 0.011215680 0.492368191 0.109902516 0.863347650
1403637172438319104 5.418738365 0.423305511 0.845408440 0.012324898 0.490728378 0.119100980 0.863046169
1403637172488318976 5.337226868 0.407600015 0.900650501 0.012780582 0.489735752 0.128555164 0.862246573
1403637172538319104 5.263380051 0.398049235 0.949776411 0.014972685 0.489081383 0.134264708 0.861712396
1403637172588318976 5.183614254 0.373659372 0.995290041 0.014877764 0.489201427 0.139394850 0.860830784
1403637172638319104 5.106465816 0.358817011 1.037030578 0.016040923 0.489116400 0.142707303 0.860315323
1403637172688318976 5.031484127 0.340559721 1.076372743 0.015690103 0.488989979 0.147058457 0.859660685
1403637172738319104 4.952849865 0.321620733 1.111229420 0.014807981 0.489582628 0.150550038 0.858734071
1403637172788318976 4.882594109 0.305728525 1.145394325 0.011670377 0.491032481 0.155419245 0.857085645
1403637172838319104 4.788956642 0.273718029 1.180091619 0.004086026 0.493788272 0.164061025 0.853955746
1403637172888318976 4.712276936 0.256017268 1.212132573 -0.004731492 0.498425990 0.173365340 0.849407792
1403637172938319104 4.640464306 0.226708710 1.245531559 -0.017455716 0.502516687 0.183314845 0.844729483
1403637172988318976 4.567240715 0.210490108 1.274541974 -0.027356153 0.506049275 0.192511633 0.840300560
1403637173038319104 4.510718822 0.217889905 1.327781796 -0.034377702 0.510213673 0.200075015 0.835745275
1403637173088318976 4.482335567 0.239096701 1.285427332 -0.039963249 0.508853137 0.203836396 0.835417330
1403637173138319104 4.428524971 0.239628315 1.306224346 -0.043718886 0.513733447 0.210676417 0.830531180
1403637173188318976 4.376324654 0.242088914 1.328611970 -0.044289432 0.520453513 0.217847437 0.824444711
1403637173238319104 4.336539268 0.248314500 1.345342278 -0.043082189 0.529296041 0.221299484 0.817934096
1403637173288318976 4.299718857 0.260925055 1.366334796 -0.037638698 0.539634228 0.222596601 0.811066568
1403637173338319104 4.263670921 0.258429050 1.380832911 -0.032511264 0.551144838 0.224139139 0.803084135
1403637173388318976 4.230763912 0.268837571 1.394444823 -0.026826967 0.562387288 0.224212125 0.795443177
1403637173438319104 4.194394112 0.270662904 1.406824112 -0.022036185 0.573654056 0.225644112 0.787096024
1403637173488318976 4.173192024 0.286693871 1.413671017 -0.017122149 0.584322989 0.225889593 0.779260755
1403637173538319104 4.150282383 0.293549538 1.420525312 -0.012684747 0.593868673 0.228897452 0.771210074
1403637173588318976 4.127433300 0.304128289 1.425505400 -0.008168137 0.603067040 0.233529329 0.762697518
1403637173638319104 4.109213829 0.311086118 1.429460764 -0.003633346 0.610652864 0.241003960 0.754325509
1403637173688318976 4.096607685 0.334306717 1.429010868 0.001011629 0.617414117 0.247703031 0.746620417
1403637173738319104 4.083759308 0.349664986 1.430748224 0.003994734 0.624295235 0.256369412 0.737912118
1403637173788318976 4.072438240 0.360131145 1.427895308 0.003995187 0.630494237 0.266174108 0.729117572
1403637173838319104 4.072259426 0.396603465 1.412901878 0.004018650 0.634529889 0.276262373 0.721827328
1403637173888318976 4.069931507 0.419414520 1.399425268 0.000091242 0.639223516 0.285821974 0.713932097
1403637173938319104 4.074057579 0.442799807 1.384586811 -0.008439695 0.645061314 0.288342565 0.707589686
1403637173988318976 4.075349331 0.455063820 1.360519886 -0.016331347 0.652609110 0.283995479 0.702268600
1403637174038319104 4.086070061 0.478366971 1.332474351 -0.023278084 0.662371695 0.268330574 0.699085593
1403637174088318976 4.095273495 0.480337739 1.299049377 -0.023584612 0.671141803 0.253441095 0.696261466
1403637174138319104 4.113788605 0.491735756 1.268293142 -0.019506564 0.680597544 0.233489931 0.694182217
1403637174188318976 4.131063938 0.493472517 1.233522654 -0.011366403 0.687728167 0.217059463 0.692665756
1403637174238319104 4.155548096 0.494747162 1.189599514 -0.001191699 0.692153454 0.204687759 0.692116380
1403637174288318976 4.179348469 0.497832894 1.149304271 0.009182489 0.694904268 0.196863383 0.691569626
1403637174338319104 4.197191238 0.495027423 1.112203598 0.014179963 0.695507586 0.195791498 0.691182971
1403637174388318976 4.216915607 0.495486140 1.068837047 0.020162098 0.694612384 0.196845070 0.691635132
1403637174438319104 4.234599590 0.491879940 1.029510498 0.028027985 0.693520248 0.201325238 0.691167295
1403637174488318976 4.247941971 0.485227346 0.985608220 0.038895480 0.692189634 0.207347423 0.690194011
1403637174538319104 4.262649059 0.476710379 0.937616527 0.043520886 0.693216562 0.210728183 0.687859237
1403637174588318976 4.277272224 0.473073959 0.886897147 0.047095556 0.695768535 0.213741645 0.684107184
1403637174638319104 4.284984112 0.462530077 0.835792720 0.044225726 0.701994777 0.212022364 0.678449631
1403637174688318976 4.302351475 0.465861976 0.774014354 0.044028200 0.710233212 0.207820266 0.671149075
1403637174738319104 4.314276695 0.468163610 0.713688254 0.041762780 0.719833672 0.202541515 0.662625313
1403637174788318976 4.324645519 0.469813824 0.657471538 0.039658070 0.730838597 0.197103858 0.652267039
1403637174838319104 4.331092358 0.474160373 0.600496173 0.036184199 0.740482688 0.197941080 0.641245186
1403637174888318976 4.336906910 0.477456331 0.542792022 0.032891124 0.748438954 0.205043688 0.629852653
1403637174938319104 4.335711002 0.479606867 0.484972596 0.030307107 0.756001830 0.213297114 0.618099511
1403637174988318976 4.343833923 0.493581533 0.421884477 0.027801052 0.763585091 0.218337089 0.607036948
1403637175038319104 4.344739914 0.499386013 0.366207361 0.027479133 0.770558536 0.222940356 0.596474707
1403637175088318976 4.348784447 0.511806846 0.302749157 0.028833505 0.777718186 0.222728908 0.587124288
1403637175138319104 4.344839573 0.520267129 0.240751386 0.033339243 0.783568025 0.221478671 0.579531610
1403637175188318976 4.348176003 0.535106122 0.180369616 0.039678302 0.789098144 0.218663111 0.572657049
1403637175238319104 4.342706203 0.541984260 0.117266178 0.047508825 0.794016361 0.215540200 0.566412747
1403637175288318976 4.336894035 0.561550558 0.053579211 0.054797489 0.798736691 0.209129080 0.561499715
1403637175338319104 4.327812672 0.571347654 -0.007147670 0.058613088 0.803164363 0.204042912 0.556648910
1403637175388318976 4.317769051 0.589276612 -0.067588925 0.061777607 0.806458533 0.199334949 0.553239226
1403637175438319104 4.310797691 0.608013391 -0.131246686 0.064173989 0.807380319 0.200755611 0.551104248
1403637175488318976 4.296853542 0.628410518 -0.194857597 0.064779058 0.806831717 0.205752417 0.549992859
1403637175538319104 4.272614479 0.647207499 -0.254525542 0.065191448 0.805185556 0.212913930 0.549630702
1403637175588318976 4.254011154 0.672345936 -0.322341025 0.063888095 0.802756488 0.220456555 0.550362766
1403637175638319104 4.223195553 0.692043185 -0.380718350 0.059955962 0.800543964 0.228676125 0.550673902
1403637175688318976 4.196987152 0.713554204 -0.443324625 0.057253629 0.798905075 0.234623641 0.550839782
1403637175738319104 4.161746025 0.731133342 -0.510262728 0.055610038 0.797073722 0.238714963 0.551902354
1403637175788318976 4.137139797 0.749672890 -0.578242302 0.051741101 0.796645164 0.240369081 0.552179396
1403637175838319104 4.101661205 0.768830001 -0.650445223 0.047565278 0.797034323 0.238253877 0.552909434
1403637175888318976 4.067447186 0.781408727 -0.721535683 0.040991757 0.798426330 0.234156772 0.553177774
1403637175938319104 4.030685902 0.798343956 -0.797276616 0.036512252 0.800195992 0.227652565 0.553649306
1403637175988318976 3.992195845 0.808674097 -0.873931527 0.034487985 0.801691890 0.220557690 0.554486275
1403637176038319104 3.953337669 0.817286372 -0.950836658 0.037847459 0.802452266 0.215378866 0.555202603
1403637176088318976 3.913788319 0.826136410 -1.023445725 0.040612388 0.803562224 0.209116265 0.555795670
1403637176138319104 3.871387005 0.833559990 -1.101194501 0.041074988 0.804443538 0.202967241 0.556765437
1403637176188318976 3.825129032 0.841259301 -1.178151846 0.042506583 0.804787874 0.197871625 0.557993233
1403637176238319104 3.779273272 0.854145050 -1.253734112 0.043307953 0.805758953 0.193648204 0.558011889
1403637176288318976 3.728298187 0.865988612 -1.328510404 0.043745253 0.806891263 0.192003191 0.556908965
1403637176338319104 3.679502249 0.881094635 -1.403619647 0.044732928 0.807728410 0.191943288 0.555636227
1403637176388318976 3.625423431 0.893943846 -1.478240728 0.042914696 0.808712482 0.191768035 0.554407358
1403637176438319104 3.571662664 0.909295082 -1.548878431 0.040984895 0.809280396 0.194211602 0.552871943
1403637176488318976 3.512818575 0.929685354 -1.621944427 0.035702664 0.810988009 0.196089134 0.550066173
1403637176538319104 3.460165977 0.949507892 -1.692402005 0.032380443 0.813221991 0.199188575 0.545843780
1403637176588318976 3.409950018 0.974849463 -1.757764697 0.032273989 0.815710247 0.203625694 0.540473640
1403637176638319104 3.336393595 0.986191094 -1.837393045 0.030142294 0.817399859 0.209875047 0.535631776
1403637176688318976 3.282569647 0.999473631 -1.893036366 0.027812494 0.819889367 0.215410247 0.529722810
1403637176738319104 3.212039471 1.034119010 -1.972862005 0.027358223 0.821095407 0.220610991 0.525722980
1403637176788318976 3.144235134 1.052137256 -2.044915915 0.025222560 0.822388411 0.224402249 0.522192240
1403637176838319104 3.088487387 1.087929726 -2.114021540 0.024152972 0.823820651 0.228022158 0.518403471
1403637176888318976 3.027109861 1.104045153 -2.169415474 0.020645553 0.824445367 0.234163418 0.514811754
1403637176938319104 2.955148935 1.124680281 -2.238377094 0.016980151 0.824656904 0.239128619 0.512318492
1403637176988318976 2.898120880 1.153923154 -2.313242435 0.012158193 0.824176967 0.244280830 0.510794818
1403637177038319104 2.820607185 1.165984273 -2.370275974 0.005988398 0.823238730 0.251813024 0.508755744
1403637177088318976 2.760025978 1.205702305 -2.444492340 -0.000526508 0.820838392 0.261726856 0.507664382
1403637177138319104 2.699928045 1.237720490 -2.510638475 -0.006607209 0.818187416 0.271766812 0.506624579
1403637177188318976 2.639505625 1.269191504 -2.578099966 -0.011465702 0.816016495 0.280456513 0.505301654
1403637177238319104 2.581534863 1.298456907 -2.651803493 -0.015855150 0.813907385 0.287630290 0.504551589
1403637177288318976 2.527738094 1.328586340 -2.723523378 -0.018198408 0.812560976 0.292187095 0.504023850
1403637177338319104 2.473414183 1.367803454 -2.793068409 -0.020671548 0.811545134 0.295599014 0.503575742
1403637177388318976 2.427819729 1.396648169 -2.864070415 -0.024040474 0.811326027 0.297192425 0.502840757
1403637177438319104 2.380453825 1.434924722 -2.938521385 -0.030069005 0.811834157 0.295894206 0.502461553
1403637177488318976 2.339237690 1.475537062 -3.016985893 -0.037700936 0.813053727 0.293835223 0.501181781
1403637177538319104 2.300976515 1.514110565 -3.092305183 -0.043526798 0.815314651 0.290817559 0.498791099
1403637177588318976 2.265694141 1.553418040 -3.169076681 -0.051450871 0.818105936 0.285370708 0.496607512
1403637177638319104 2.237535000 1.592535019 -3.247162819 -0.057488270 0.821206272 0.278093934 0.494953662
1403637177688318976 2.208042622 1.625685215 -3.330031872 -0.061056457 0.824252546 0.270630956 0.493597686
1403637177738319104 2.186304331 1.661043763 -3.404466629 -0.066025846 0.827595890 0.261055291 0.492519826
1403637177788318976 2.173272610 1.682652950 -3.484927177 -0.064309381 0.830950260 0.256099641 0.489692628
1403637177838319104 2.159399509 1.708579421 -3.560260296 -0.060074821 0.833374321 0.256723255 0.485768855
1403637177888318976 2.149758816 1.734833002 -3.641475916 -0.056462038 0.836374819 0.258023709 0.480325818
1403637177938319104 2.142354012 1.753356576 -3.701840401 -0.054298773 0.840978265 0.258695304 0.472105801
1403637177988318976 2.132209539 1.796653390 -3.795916557 -0.055564020 0.844823360 0.258356512 0.465229005
1403637178038319104 2.140405416 1.790253878 -3.855081558 -0.063510329 0.851071417 0.257216752 0.453302741
1403637178088318976 2.156025648 1.839378357 -3.915368080 -0.071645103 0.858972788 0.250565648 0.440737545
1403637178138319104 2.143008709 1.863020182 -4.013344288 -0.076393984 0.863021612 0.249151945 0.432759672
1403637178188318976 2.156686306 1.893352032 -4.083408356 -0.081223495 0.867681623 0.248081118 0.423068672
1403637178238319104 2.163019180 1.900166273 -4.141191483 -0.085207209 0.872406065 0.244661584 0.414473236
1403637178288318976 2.187931061 1.928575993 -4.195850372 -0.088350132 0.877088308 0.238779441 0.407301694
1403637178338319104 2.203621149 1.955173135 -4.269500256 -0.091041744 0.881201863 0.230276331 0.402700245
1403637178388318976 2.225424290 1.961851835 -4.321533203 -0.096075132 0.884326458 0.225955606 0.397089899
1403637178438319104 2.264031410 2.002773523 -4.386511326 -0.098197311 0.887242317 0.218945220 0.393981397
1403637178488318976 2.293334961 2.016066790 -4.434159279 -0.099397786 0.888796806 0.217599824 0.390910029
1403637178538319104 2.337821484 2.019765139 -4.480131149 -0.098140210 0.889936149 0.217764929 0.388536453
1403637178588318976 2.377908945 2.020529032 -4.523302078 -0.096303947 0.890568376 0.218377411 0.387201250
1403637178638319104 2.420469999 2.027308464 -4.557628632 -0.087420084 0.891169190 0.219866693 0.387083679
1403637178688318976 2.471217155 2.029634953 -4.593241215 -0.076932646 0.891470253 0.221024722 0.387956411
1403637178738319104 2.522699356 2.032128572 -4.619957447 -0.064426951 0.892541707 0.219966978 0.388372213
1403637178788318976 2.575849533 2.038423777 -4.649454117 -0.052158799 0.893219411 0.218008250 0.389757514
1403637178838319104 2.629504681 2.043020248 -4.672458649 -0.041890811 0.894000709 0.215683192 0.390497953
1403637178888318976 2.688147306 2.043991566 -4.693852425 -0.030294606 0.893805325 0.216840237 0.391375273
1403637178938319104 2.744569302 2.050057650 -4.714525223 -0.020458641 0.893430769 0.217440799 0.392533213
1403637178988318976 2.800988197 2.060685635 -4.727120399 -0.013608609 0.893654287 0.215747371 0.393255442
1403637179038319104 2.857160091 2.061705828 -4.742976189 -0.007742741 0.893353820 0.215351120 0.394313127
1403637179088318976 2.910499334 2.072850704 -4.751901150 -0.005907809 0.892717659 0.216764376 0.395010769
1403637179138319104 2.966472626 2.085416317 -4.758491993 -0.007016447 0.891395211 0.221036106 0.395611465
1403637179188318976 3.015430450 2.093453407 -4.768589973 -0.007498074 0.890013099 0.224134803 0.396968544
1403637179238319104 3.071753740 2.103185654 -4.770906448 -0.011329191 0.888938785 0.227144271 0.397573769
1403637179288318976 3.124252319 2.114107132 -4.776267529 -0.013937785 0.888078213 0.228226751 0.398792356
1403637179338319104 3.174170494 2.110069275 -4.775436878 -0.017572328 0.888078213 0.228435099 0.398529440
1403637179388318976 3.225692034 2.102662563 -4.780313492 -0.019777818 0.887355447 0.229542315 0.399398863
1403637179438319104 3.280392408 2.086637974 -4.781868935 -0.021965645 0.886886775 0.230401054 0.399830818
1403637179488318976 3.331040859 2.079199791 -4.787738323 -0.021502951 0.886246145 0.230797708 0.401045799
1403637179538319104 3.382392168 2.058461189 -4.780563354 -0.021408577 0.886368513 0.231227264 0.400532752
1403637179588318976 3.438732147 2.039418936 -4.782860756 -0.021765672 0.886504471 0.230766237 0.400478512
1403637179638319104 3.480081081 2.043131113 -4.776000023 -0.019824967 0.886810720 0.229426146 0.400671154
1403637179688318976 3.531880140 2.043051243 -4.771340370 -0.019581117 0.887463033 0.227268711 0.400468230
1403637179738319104 3.591107607 2.038092375 -4.761534214 -0.022615310 0.888469815 0.225475132 0.399087608
1403637179788318976 3.641178608 2.048532009 -4.748771667 -0.028378703 0.889621854 0.222573712 0.397779465
1403637179838319104 3.695586205 2.071764469 -4.733490467 -0.035971716 0.891579449 0.215589121 0.396627545
1403637179888318976 3.746973038 2.089502335 -4.721399784 -0.043251123 0.893187940 0.209499553 0.395543426
1403637179938319104 3.807899475 2.103815079 -4.702613831 -0.047941398 0.894527555 0.204986900 0.394337922
1403637179988318976 3.860338926 2.122672796 -4.682617188 -0.049452595 0.894699335 0.202870339 0.394855797
1403637180038319104 3.917412043 2.148264408 -4.651984215 -0.043847706 0.894183159 0.206239164 0.394942135
1403637180088318976 3.986884117 2.165305614 -4.623009205 -0.040078156 0.893165529 0.210170582 0.395572186
1403637180138319104 4.039725780 2.183226824 -4.591802597 -0.031960625 0.891685665 0.214773044 0.397174656
1403637180188318976 4.099133015 2.196338892 -4.558102131 -0.024928229 0.889724255 0.220483974 0.398943812
1403637180238319104 4.155570030 2.212958813 -4.525958538 -0.018842395 0.888082504 0.223393396 0.401310176
1403637180288318976 4.233356953 2.227904558 -4.470176697 -0.013043379 0.887923121 0.227192000 0.399757683
1403637180338319104 4.290166855 2.226757765 -4.435030460 -0.011034155 0.886442542 0.229914889 0.401543230
1403637180388318976 4.348496914 2.223775387 -4.385924816 -0.009511718 0.884662092 0.237981468 0.400808305
1403637180438319104 4.400732994 2.214599133 -4.359293461 -0.011273528 0.880885005 0.249129117 0.402304977
1403637180488318976 4.453615189 2.222085476 -4.320775986 -0.013643156 0.877863407 0.258441865 0.402961016
1403637180538319104 4.507924557 2.221435547 -4.288050652 -0.015540229 0.875328183 0.266069859 0.403442532
1403637180588318976 4.568750381 2.217036963 -4.247414589 -0.018989958 0.874982178 0.268798769 0.402234793
1403637180638319104 4.629100323 2.198214293 -4.214188099 -0.026952738 0.876918912 0.262593210 0.401661187
1403637180688318976 4.682150841 2.198393345 -4.185482025 -0.027498361 0.879639566 0.252905637 0.401891649
1403637180738319104 4.756961346 2.169189930 -4.139246941 -0.028202279 0.882242203 0.248548195 0.398844779
1403637180788318976 4.834011555 2.164482117 -4.096099854 -0.028845277 0.885613203 0.240653232 0.396160692
1403637180838319104 4.887708187 2.145926476 -4.070521832 -0.030802092 0.886746228 0.236774951 0.395815700
1403637180888318976 4.953244209 2.124433517 -4.034242630 -0.036580216 0.889235735 0.231036156 0.393120885
1403637180938319104 5.020518780 2.099095583 -3.992434740 -0.041669112 0.890898407 0.228637919 0.390241534
1403637180988318976 5.090706825 2.069003105 -3.969821453 -0.047917169 0.891813397 0.226026714 0.388953418
1403637181038319104 5.150571346 2.051742315 -3.910669804 -0.054233450 0.894473135 0.221120819 0.384814411
1403637181088318976 5.216210842 2.023747444 -3.875841618 -0.053265885 0.894456804 0.221647680 0.384684533
1403637181138319104 5.283357620 1.993847132 -3.843031645 -0.046167478 0.894219875 0.225178495 0.384101599
1403637181188318976 5.353708267 1.958649397 -3.792567253 -0.037283756 0.894054949 0.229107097 0.383126169
1403637181238319104 5.422286987 1.933058977 -3.758444786 -0.026312212 0.893530846 0.230880067 0.384193540
1403637181288318976 5.498073578 1.891389847 -3.702044010 -0.017767824 0.894529104 0.231760323 0.381823480
1403637181338319104 5.564059734 1.854190111 -3.657731533 -0.012249519 0.895258605 0.229278639 0.381828904
1403637181388318976 5.634198189 1.815179825 -3.604757786 -0.010094583 0.896940470 0.225184917 0.380378366
1403637181438319104 5.706047058 1.777893782 -3.549681664 -0.010086330 0.898473978 0.221840173 0.378721118
1403637181488318976 5.768633366 1.750705481 -3.495249271 -0.011640185 0.899051249 0.220115811 0.378312469
1403637181538319104 5.833937645 1.688360453 -3.446109772 -0.015736034 0.898492098 0.224034190 0.377190977
1403637181588318976 5.903284073 1.658899665 -3.382931709 -0.015871355 0.898793042 0.225658387 0.375496358
1403637181638319104 5.972661972 1.598857880 -3.333734512 -0.017469864 0.898116887 0.230408669 0.374156058
1403637181688318976 6.034139633 1.535622835 -3.286117077 -0.018297706 0.897495091 0.233631447 0.373609573
1403637181738319104 6.107645035 1.499250889 -3.220891237 -0.014949339 0.897989929 0.235168830 0.371599585
1403637181788318976 6.177015305 1.456175208 -3.155407429 -0.010046268 0.899006546 0.234978884 0.369420081
1403637181838319104 6.238402367 1.399998069 -3.109702110 -0.006134633 0.898698211 0.235922769 0.369654238
1403637181888318976 6.300718307 1.356128097 -3.047996044 -0.003423136 0.899203420 0.235550851 0.368696839
1403637181938319104 6.366537094 1.305602074 -2.989622116 -0.002355542 0.898981512 0.237278000 0.368138343
1403637181988318976 6.430664539 1.265226364 -2.929195404 -0.000538765 0.899313271 0.236494675 0.367839247
1403637182038319104 6.495517731 1.216032743 -2.869681597 -0.000199365 0.899588585 0.235488474 0.367811769
1403637182088318976 6.562236786 1.176133394 -2.807519436 0.002042088 0.900893748 0.230924174 0.367505491
1403637182138319104 6.619000435 1.121103764 -2.751757383 0.004839997 0.900562465 0.229986608 0.368876666
1403637182188318976 6.672159195 1.087317467 -2.692182302 0.011435261 0.900198162 0.227328405 0.371260405
1403637182238319104 6.736076832 1.048920035 -2.621601343 0.017857064 0.900653958 0.224535927 0.371600837
1403637182288318976 6.787786484 0.995972872 -2.562146187 0.023859868 0.899394631 0.225197792 0.373906314
1403637182338319104 6.843237877 0.961382389 -2.495914221 0.029822946 0.899270594 0.222800806 0.375210404
1403637182388318976 6.889414310 0.934891701 -2.434021950 0.034390114 0.898880124 0.219592154 0.377638966
1403637182438319104 6.959433079 0.891369343 -2.363271713 0.038989455 0.899406016 0.217215493 0.377314329
1403637182488318976 7.014538765 0.874653935 -2.295472622 0.038198397 0.901390910 0.207762852 0.377981305
1403637182538319104 7.062627792 0.832701206 -2.223721504 0.035750072 0.902383268 0.203817397 0.378001094
1403637182588318976 7.100219727 0.779867887 -2.161768675 0.030891687 0.903023362 0.200733542 0.378550559
1403637182638319104 7.119421005 0.740224838 -2.100612164 0.029195774 0.902394772 0.199683771 0.380733132
1403637182688318976 7.161037445 0.699859381 -2.027744293 0.028621949 0.902330875 0.200011387 0.380756050
1403637182738319104 7.188076019 0.650937796 -1.958201408 0.030486964 0.901756525 0.200577229 0.381673276
1403637182788318976 7.210247040 0.610358953 -1.883951664 0.034099188 0.900823593 0.202658966 0.382470191
1403637182838319104 7.236079216 0.571185946 -1.816167355 0.038768355 0.899939895 0.205001518 0.382857084
1403637182888318976 7.276163101 0.519546032 -1.727139473 0.040219825 0.900479436 0.206601098 0.380572081
1403637182938319104 7.289410591 0.484790564 -1.657716274 0.046071511 0.899727046 0.207658291 0.381112456
1403637182988318976 7.306585312 0.452112198 -1.578526974 0.051515494 0.899184942 0.209076092 0.380919605
1403637183038319104 7.320601463 0.417015076 -1.505428314 0.057834525 0.898095429 0.212042496 0.380943269
1403637183088318976 7.328146935 0.388835669 -1.427032232 0.063287795 0.897255480 0.213310882 0.381347239
1403637183138319104 7.344299316 0.362824678 -1.342355728 0.067915834 0.896468341 0.215724319 0.381044596
1403637183188318976 7.348315239 0.344950199 -1.261410236 0.071257919 0.895743847 0.217310935 0.381236374
1403637183238319104 7.349061489 0.329681396 -1.181317091 0.074100927 0.894910574 0.219314933 0.381503761
1403637183288318976 7.353745461 0.312590837 -1.093568802 0.075419888 0.894619226 0.220928997 0.380996883
1403637183338319104 7.346811295 0.299245834 -1.015224934 0.077978946 0.893655121 0.223401532 0.381302476
1403637183388318976 7.336434841 0.288649917 -0.933726788 0.080209523 0.892932475 0.225327224 0.381399691
1403637183438319104 7.316450596 0.280886769 -0.860331059 0.081474870 0.892643750 0.225556180 0.381671786
1403637183488318976 7.300057888 0.268228650 -0.776386499 0.081842065 0.892870367 0.225649714 0.381007373
1403637183538319104 7.280042648 0.262715101 -0.697240591 0.083541572 0.892229259 0.227399468 0.381099969
1403637183588318976 7.256420135 0.255214453 -0.614044905 0.085489735 0.891836286 0.228346094 0.381021798
1403637183638319104 7.229216576 0.246909499 -0.532602787 0.087653838 0.891372383 0.229622856 0.380848199
1403637183688318976 7.197180271 0.248250008 -0.456382036 0.089954734 0.891274095 0.229685634 0.380503774
1403637183738319104 7.160860538 0.246143579 -0.379508972 0.092195183 0.890034378 0.233306751 0.380666226
1403637183788318976 7.112443447 0.226960659 -0.306096077 0.094944835 0.887285233 0.241089284 0.381557673
1403637183838319104 7.076683998 0.231884956 -0.225282669 0.096884146 0.885688901 0.246594295 0.381260961
1403637183888318976 7.029503345 0.224266887 -0.154800892 0.099794298 0.883530498 0.253019512 0.381308347
1403637183938319104 6.964408875 0.232476592 -0.084514141 0.102858327 0.881588936 0.257171303 0.382209450
1403637183988318976 6.903884888 0.222411275 -0.031203508 0.104798988 0.879450142 0.263401836 0.382366359
1403637184038319104 6.837439537 0.215090275 0.037140608 0.106785409 0.878063619 0.267622262 0.382072598
1403637184088318976 6.772472382 0.197124720 0.097084522 0.106935382 0.877496243 0.270928711 0.381002307
1403637184138319104 6.702638149 0.184279442 0.150105238 0.104218297 0.877827168 0.272003144 0.380226672
1403637184188318976 6.618656158 0.167499900 0.199984789 0.100198083 0.878068328 0.272944689 0.380075663
1403637184238319104 6.539635658 0.163308620 0.252342224 0.093208477 0.880197644 0.270143062 0.378928810
1403637184288318976 6.455919266 0.165592551 0.289529800 0.081953809 0.882297635 0.267289340 0.378669769
1403637184338319104 6.366777420 0.160367608 0.332574129 0.069205210 0.884311020 0.265585989 0.377715200
1403637184388318976 6.281391621 0.169670582 0.375248671 0.056616444 0.885534704 0.264852643 0.377459794
1403637184438319104 6.191041946 0.168963194 0.421892643 0.045976955 0.886058390 0.266062409 0.376825452
1403637184488318976 6.103943825 0.179359555 0.461813688 0.037780240 0.885307014 0.269690305 0.376923412
1403637184538319104 6.014438629 0.190533280 0.503177404 0.031118248 0.884383678 0.273425370 0.377008855
1403637184588318976 5.923927307 0.200914264 0.542515039 0.025240161 0.882594943 0.279363960 0.377286255
1403637184638319104 5.834465981 0.213880658 0.579000711 0.020663580 0.881062388 0.284032613 0.377660602
1403637184688318976 5.746839523 0.223555803 0.617730021 0.016728980 0.879536986 0.288604021 0.377945095
1403637184738319104 5.660369396 0.242268443 0.645334244 0.014905448 0.877665997 0.293927282 0.378268421
1403637184788318976 5.573585987 0.258725047 0.673997998 0.012708887 0.876464903 0.297193021 0.378581613
1403637184838319104 5.485247612 0.264985919 0.705264330 0.009948831 0.875355065 0.299970239 0.379041374
1403637184888318976 5.400402546 0.268674731 0.730891943 0.008458842 0.874550223 0.302173108 0.379185617
1403637184938319104 5.317482948 0.275517702 0.747945428 0.005704642 0.873900175 0.303606331 0.379590660
1403637184988318976 5.236901283 0.284199238 0.766658068 0.007025615 0.873186767 0.305567980 0.379636347
1403637185038319104 5.155281067 0.286625862 0.785328150 0.002618727 0.872888684 0.306410432 0.379698724
1403637185088318976 5.080495358 0.284726381 0.799851537 0.002622823 0.872528195 0.308349818 0.378956497
1403637185138319104 5.007130146 0.289269090 0.805797935 0.001896177 0.872192442 0.309013426 0.379193127
1403637185188318976 4.934314728 0.287514806 0.811821222 0.001305098 0.872391820 0.309146106 0.378628403
1403637185238319104 4.861620903 0.286700130 0.812497139 0.000215475 0.871853352 0.310905308 0.378430426
1403637185288318976 4.783780098 0.284594059 0.813748002 -0.000994447 0.871030211 0.313345224 0.378312171
1403637185338319104 4.720858574 0.287201047 0.803688288 -0.006081566 0.870262265 0.315029800 0.378632933
1403637185388318976 4.653111935 0.289134741 0.798206687 -0.012222999 0.870101154 0.315927356 0.378106475
1403637185438319104 4.588677406 0.290787339 0.788548827 -0.018135378 0.869764388 0.316874713 0.377851129
1403637185488318976 4.526393414 0.290510535 0.774012446 -0.020737257 0.869703591 0.316834241 0.377891153
1403637185538319104 4.473567009 0.282781601 0.753678322 -0.021498835 0.870395899 0.315978587 0.376969904
1403637185588318976 4.423390865 0.255227923 0.737251401 -0.021099716 0.872064412 0.312292427 0.376207262
1403637185638319104 4.368418217 0.237863183 0.713571906 -0.016625127 0.874592423 0.305944920 0.375778407
1403637185688318976 4.325229645 0.225042224 0.686502099 -0.013320826 0.877906382 0.296730459 0.375571489
1403637185738319104 4.274240494 0.213371277 0.661459923 -0.008803351 0.880783021 0.288369298 0.375482231
1403637185788318976 4.230658054 0.204441428 0.633751273 -0.009105789 0.883537412 0.280689329 0.374822855
1403637185838319104 4.185870647 0.195180297 0.608207822 -0.010581634 0.885191917 0.276014686 0.374351650
1403637185888318976 4.142685890 0.191346407 0.584274888 -0.009656970 0.886833608 0.271395922 0.373867840
1403637185938319104 4.112356186 0.193876505 0.556294441 -0.009351477 0.888225913 0.267489076 0.373385608
1403637185988318976 4.070233345 0.179267287 0.528096676 -0.008600194 0.888953388 0.264647961 0.373696893
1403637186038319104 4.030396461 0.179908633 0.500536203 -0.004581258 0.889969766 0.261288762 0.373712510
1403637186088318976 3.990872383 0.176366806 0.471199512 -0.003409415 0.890645623 0.258549899 0.374019623
1403637186138319104 3.967913628 0.175300002 0.451514006 -0.003427360 0.891620219 0.256309181 0.373238832
1403637186188318976 3.923256159 0.163909733 0.424571514 -0.001861295 0.891476333 0.256141037 0.373708785
1403637186238319104 3.887395620 0.161251307 0.394646883 -0.001900616 0.891204536 0.256577522 0.374057293
1403637186288318976 3.862588406 0.147723734 0.370314956 -0.004162373 0.891376078 0.256665438 0.373569459
1403637186338319104 3.820771694 0.132089376 0.343825579 -0.002457266 0.892005146 0.254198432 0.373769879
1403637186388318976 3.789598942 0.122385740 0.316047668 0.000143073 0.892496645 0.253011703 0.373409718
1403637186438319104 3.752531528 0.100971282 0.292084336 0.002696142 0.892463982 0.252884507 0.373564184
1403637186488318976 3.721875668 0.085738897 0.265006661 0.006668115 0.892460942 0.253163606 0.373332500
1403637186538319104 3.695806742 0.069915891 0.237353802 0.011624423 0.892463028 0.253225237 0.373164296
1403637186588318976 3.664582253 0.048926115 0.206789255 0.013385971 0.892437994 0.253259212 0.373142004
1403637186638319104 3.627992153 0.027258277 0.184203982 0.015180457 0.892550170 0.254023969 0.372284174
1403637186688318976 3.603015423 0.017520428 0.153933883 0.016083417 0.892215788 0.255314201 0.372165352
1403637186738319104 3.572776794 0.002759695 0.131615996 0.017738588 0.891068161 0.259735972 0.371779710
1403637186788318976 3.537354946 -0.002565265 0.108763456 0.022627834 0.889639854 0.264765203 0.371386975
1403637186838319104 3.501027107 -0.024141312 0.084864855 0.027811719 0.887406766 0.271107644 0.371801496
1403637186888318976 3.482804775 -0.023685694 0.059413075 0.034057274 0.885910690 0.276034504 0.371224016
1403637186938319104 3.443638086 -0.033963919 0.035210371 0.041801352 0.884178936 0.280072927 0.371536583
1403637186988318976 3.409667492 -0.039066911 0.010895371 0.047514930 0.882807195 0.283647478 0.371399909
1403637187038319104 3.371207714 -0.040178180 -0.020484805 0.053109072 0.882175624 0.283823639 0.372007728
1403637187088318976 3.339482307 -0.041615367 -0.051705956 0.055062145 0.882689059 0.282097638 0.371818721
1403637187138319104 3.292577028 -0.046435833 -0.081878185 0.054557960 0.883548856 0.279568315 0.371761173
1403637187188318976 3.259603024 -0.041118264 -0.113304973 0.051078387 0.885249376 0.276783258 0.370291173
1403637187238319104 3.213974476 -0.039519548 -0.143050194 0.045780450 0.886502266 0.277454853 0.367473394
1403637187288318976 3.172204256 -0.019083977 -0.180295825 0.037996531 0.886959493 0.280839980 0.364675254
1403637187338319104 3.135006428 -0.007821321 -0.215525866 0.029611392 0.887477100 0.284811318 0.361095697
1403637187388318976 3.093359947 0.006399512 -0.247057796 0.020716671 0.888154626 0.287535727 0.357876271
1403637187438319104 3.053653240 0.023070812 -0.285194814 0.013681013 0.888641953 0.289815694 0.355155200
1403637187488318976 3.017364025 0.042470455 -0.321657956 0.009346990 0.889013410 0.292002052 0.352565736
1403637187538319104 2.982227087 0.058250189 -0.356758833 0.005725848 0.889204085 0.294371694 0.350183576
1403637187588318976 2.942302227 0.070058823 -0.398623466 0.003914735 0.889179885 0.296450347 0.348512501
1403637187638319104 2.903801918 0.086705923 -0.441240072 0.003933567 0.888984978 0.298441887 0.347307801
1403637187688318976 2.873047829 0.104890704 -0.479692757 0.005329748 0.889170229 0.299647808 0.345773131
1403637187738319104 2.836099148 0.122084975 -0.523192167 0.006014410 0.888822496 0.301807195 0.344776392
1403637187788318976 2.808159351 0.141077280 -0.570261240 0.005828697 0.888910472 0.302892357 0.343599170
1403637187838319104 2.770008564 0.159812689 -0.615316987 0.006391775 0.888060689 0.305585802 0.343401670
1403637187888318976 2.740786552 0.177187681 -0.660187960 0.004280634 0.888189197 0.306232482 0.342524797
1403637187938319104 2.713878155 0.199704409 -0.706440508 0.000971099 0.888657510 0.305600792 0.341899037
1403637187988318976 2.688482285 0.223527133 -0.753747404 -0.000084172 0.889585257 0.303569257 0.341297209
1403637188038319104 2.664435863 0.244570136 -0.804065824 -0.002564409 0.890828550 0.300757289 0.340533316
1403637188088318976 2.646141529 0.273844600 -0.849748015 -0.004762156 0.892273903 0.297359467 0.339708567
1403637188138319104 2.622605562 0.295678973 -0.898516774 -0.005865038 0.893668711 0.293744862 0.339169264
1403637188188318976 2.594900846 0.324853420 -0.963108540 -0.009884510 0.895682931 0.287136227 0.339421928
1403637188238319104 2.575943947 0.352735043 -1.022780061 -0.014487457 0.898563445 0.278154999 0.339121819
1403637188288318976 2.561213493 0.375710547 -1.066752672 -0.015976820 0.901151240 0.271238536 0.337788105
1403637188338319104 2.544821739 0.391766369 -1.131423593 -0.016109793 0.902257085 0.268120110 0.337319195
1403637188388318976 2.524970055 0.415704608 -1.191444635 -0.012753566 0.903476119 0.263562292 0.337791532
1403637188438319104 2.516184807 0.440490186 -1.241000175 -0.009491852 0.904818535 0.259981334 0.337080181
1403637188488318976 2.497831821 0.463926435 -1.295433402 -0.005924249 0.906092942 0.257197350 0.335872054
1403637188538319104 2.488343239 0.484568238 -1.340553880 -0.001604421 0.907701313 0.255168110 0.333114028
1403637188588318976 2.463289022 0.503601611 -1.405132890 0.003478500 0.908228695 0.256665587 0.330501497
1403637188638319104 2.460581779 0.543601751 -1.457074046 0.007932813 0.910241425 0.255983591 0.325376689
1403637188688318976 2.447819233 0.580568194 -1.507122040 0.016347187 0.911504805 0.258191586 0.319732428
1403637188738319104 2.435004711 0.613894701 -1.558067322 0.024835249 0.913226247 0.260118425 0.312633038
1403637188788318976 2.418463230 0.657035768 -1.623700857 0.034258686 0.914093018 0.263710409 0.306132466
1403637188838319104 2.419079781 0.694179893 -1.660136580 0.040221546 0.916133642 0.266519219 0.296730340
1403637188888318976 2.400492191 0.723708272 -1.716714025 0.044007774 0.917330325 0.269781321 0.289458871
1403637188938319104 2.381639957 0.762598932 -1.762769461 0.045193739 0.918715179 0.271693528 0.283023953
1403637188988318976 2.356116295 0.792554736 -1.821578503 0.042204954 0.919465959 0.275010824 0.277795136
1403637189038319104 2.325886965 0.827494383 -1.888914824 0.035746355 0.920085013 0.277800202 0.273848057
1403637189088318976 2.309632778 0.856041610 -1.940115690 0.029037073 0.920458496 0.281733245 0.269331217
1403637189138319104 2.291310787 0.879373014 -1.980224133 0.021936839 0.919886768 0.287737608 0.265582591
1403637189188318976 2.269803762 0.911944807 -2.035491467 0.018783629 0.918979466 0.292968899 0.263235867
1403637189238319104 2.245255470 0.934518576 -2.085200071 0.017862752 0.917745113 0.298805952 0.261036009
1403637189288318976 2.226425409 0.967210054 -2.137923717 0.020520145 0.917123735 0.301652640 0.259747446
1403637189338319104 2.202406883 1.005539656 -2.192177534 0.025734678 0.917437315 0.300670207 0.259314239
1403637189388318976 2.188532114 1.037911773 -2.246083498 0.029237669 0.919031560 0.296069980 0.258589983
1403637189438319104 2.166062593 1.078149319 -2.301947594 0.031635467 0.921429873 0.288085073 0.258791655
1403637189488318976 2.140934467 1.111080170 -2.356138468 0.033154309 0.923227847 0.281981617 0.258915991
1403637189538319104 2.124164343 1.146143198 -2.415382385 0.031073105 0.924702168 0.277062178 0.259223759
1403637189588318976 2.101409435 1.182691216 -2.474679470 0.028066145 0.925879002 0.272551298 0.260146409
1403637189638319104 2.076540709 1.211529493 -2.529845238 0.024638470 0.926751852 0.269518524 0.260545135
1403637189688318976 2.051397562 1.238680005 -2.588478804 0.021867804 0.927534759 0.266171575 0.261445463
1403637189738319104 2.028556108 1.260570884 -2.642781973 0.019642957 0.927028835 0.267495781 0.262064338
1403637189788318976 2.003176689 1.288215399 -2.702989340 0.018267790 0.926472425 0.268606573 0.262993634
1403637189838319104 1.976145744 1.314445734 -2.766543627 0.015386614 0.925857425 0.269939840 0.263976961
1403637189888318976 1.949241042 1.319647431 -2.816422701 0.014858609 0.926077366 0.269504935 0.263679743
1403637189938319104 1.925151587 1.335595250 -2.877079725 0.015860241 0.926322162 0.267926186 0.264369607
1403637189988318976 1.903505087 1.354838610 -2.930072308 0.014315727 0.927189231 0.265506983 0.263858199
1403637190038319104 1.875401258 1.370863199 -2.997048378 0.015100203 0.927698970 0.263362080 0.264172375
1403637190088318976 1.852996826 1.380175114 -3.053354263 0.013849468 0.928668201 0.260816991 0.263359070
1403637190138319104 1.829845428 1.392230511 -3.104090214 0.014578174 0.929163396 0.259748548 0.262628227
1403637190188318976 1.803703785 1.389200449 -3.154244900 0.014082986 0.929867029 0.258123159 0.261765927
1403637190238319104 1.776267409 1.397290587 -3.219239235 0.016437076 0.929799199 0.258004516 0.261986405
1403637190288318976 1.762915134 1.389883280 -3.267206907 0.015782192 0.930390537 0.257652193 0.260268688
1403637190338319104 1.722316980 1.393640995 -3.323215961 0.016468380 0.930370331 0.257337868 0.260609001
1403637190388318976 1.692030668 1.392360449 -3.378186464 0.017712884 0.930330276 0.257893950 0.260120362
1403637190438319104 1.675142288 1.398901224 -3.440441608 0.019961394 0.930313408 0.258074164 0.259838820
1403637190488318976 1.653608084 1.387830973 -3.490827084 0.020123346 0.930848002 0.257336468 0.258640647
1403637190538319104 1.611274481 1.402617216 -3.547246933 0.019218605 0.931083560 0.256633788 0.258559793
1403637190588318976 1.594007730 1.380144477 -3.592351437 0.015254994 0.931545377 0.256498426 0.257291645
1403637190638319104 1.560166121 1.394888163 -3.636133671 0.010638775 0.931859076 0.254158735 0.258705974
1403637190688318976 1.534294844 1.385576606 -3.687854290 0.005845605 0.931121111 0.253545403 0.262095571
1403637190738319104 1.507189393 1.400917768 -3.735548019 0.006114348 0.929301977 0.253408998 0.268596977
1403637190788318976 1.477116585 1.393252611 -3.764831066 0.006969209 0.927855432 0.253224462 0.273702532
1403637190838319104 1.470885515 1.398413658 -3.810534239 0.008481316 0.926069260 0.253362119 0.279520005
1403637190888318976 1.432804704 1.384245157 -3.845011950 0.011213469 0.924066186 0.254222333 0.285213828
1403637190938319104 1.412138224 1.395122766 -3.893385887 0.014046599 0.922491550 0.254045606 0.290297896
1403637190988318976 1.389875174 1.432179570 -3.935054302 0.017404873 0.921256840 0.252164394 0.295628279
1403637191038319104 1.361784458 1.443970680 -3.969640255 0.018272793 0.920365155 0.250788838 0.299497962
1403637191088318976 1.333939433 1.457375050 -4.004919529 0.019920288 0.919616640 0.249562368 0.302699536
1403637191138319104 1.308493137 1.466293573 -4.049597740 0.020386072 0.918711364 0.249607325 0.305368602
1403637191188318976 1.285594940 1.484530926 -4.077907562 0.019906234 0.918540359 0.248198867 0.307058036
1403637191238319104 1.258395314 1.493419170 -4.107958794 0.019452332 0.918297350 0.248392731 0.307656735
1403637191288318976 1.233572602 1.517131090 -4.145876884 0.017844262 0.918118775 0.247269616 0.309188008
1403637191338319104 1.206912875 1.528335094 -4.175854683 0.017856045 0.918039501 0.246763349 0.309826553
1403637191388318976 1.179610252 1.540820122 -4.193407059 0.015097840 0.918783963 0.244794458 0.309327960
1403637191438319104 1.158208489 1.558982611 -4.217263699 0.013324044 0.919330657 0.243553787 0.308763981
1403637191488318976 1.122612238 1.573276281 -4.248307228 0.013238160 0.919384539 0.242867574 0.309147567
1403637191538319104 1.092862248 1.564196706 -4.262139797 0.009264102 0.920060515 0.242913395 0.307239145
1403637191588318976 1.067472458 1.600262046 -4.302804947 0.006364428 0.920364678 0.241589278 0.307446003
1403637191638319104 1.041970491 1.609173775 -4.329458714 0.001665117 0.919748843 0.244897783 0.306731761
1403637191688318976 1.016983747 1.625983953 -4.347139835 -0.001021362 0.918922901 0.249990746 0.305097193
1403637191738319104 0.984262824 1.607248068 -4.365347385 -0.002906965 0.917626858 0.256324679 0.303727001
1403637191788318976 0.953269124 1.606283545 -4.386615753 -0.006034906 0.916695476 0.261260808 0.302284271
1403637191838319104 0.926426411 1.604122519 -4.398661137 -0.012060345 0.917126596 0.261353523 0.300711900
1403637191888318976 0.906719565 1.603904486 -4.416486740 -0.019145023 0.917751431 0.260239065 0.299401730
1403637191938319104 0.874880075 1.605304480 -4.453860283 -0.025380790 0.918172061 0.258390427 0.299249440
1403637191988318976 0.858946800 1.594459772 -4.468142033 -0.031184783 0.918681562 0.257493436 0.297907382
1403637192038319104 0.837250471 1.580823183 -4.489133358 -0.033460241 0.918060184 0.260866255 0.296638995
1403637192088318976 0.821039081 1.567591310 -4.506746292 -0.033193856 0.916673839 0.266848952 0.295633048
1403637192138319104 0.796457410 1.565201283 -4.530807495 -0.033631824 0.915439367 0.271136791 0.295507073
1403637192188318976 0.787142277 1.543837070 -4.555897236 -0.035376523 0.914235890 0.275451392 0.295038491
1403637192238319104 0.778260469 1.531145692 -4.574455261 -0.038053568 0.913908899 0.276680797 0.294567764
1403637192288318976 0.776438713 1.513587594 -4.602341652 -0.043523107 0.914015949 0.276204109 0.293924987
1403637192338319104 0.764664650 1.489374638 -4.613889694 -0.047884408 0.914848149 0.274056464 0.292665333
1403637192388318976 0.761316299 1.465940237 -4.627658367 -0.049273632 0.915799141 0.271122754 0.292192668
1403637192438319104 0.763369799 1.447275043 -4.641997814 -0.047296070 0.915657103 0.272175431 0.291985810
1403637192488318976 0.763297439 1.427947283 -4.661204338 -0.040291671 0.914327323 0.277942538 0.291770548
1403637192538319104 0.769809008 1.417127013 -4.681338787 -0.033785943 0.912935853 0.282826900 0.292259336
1403637192588318976 0.781639099 1.397955656 -4.695981026 -0.028059639 0.911280930 0.288626790 0.292359889
1403637192638319104 0.792402506 1.385528684 -4.706777573 -0.023785289 0.909995973 0.292944580 0.292446613
1403637192688318976 0.807639599 1.376712918 -4.727383614 -0.020387806 0.908899426 0.296593845 0.292434990
1403637192738319104 0.819553971 1.368943691 -4.741514206 -0.018858755 0.908738911 0.296972185 0.292652518
1403637192788318976 0.831473112 1.365837336 -4.759379864 -0.017800137 0.908885777 0.296006739 0.293240219
1403637192838319104 0.850950480 1.355420113 -4.776287079 -0.017658308 0.909593582 0.293524474 0.293549091
1403637192888318976 0.872607350 1.343853712 -4.799609184 -0.016892591 0.910725713 0.290160656 0.293428242
1403637192938319104 0.888301134 1.341311693 -4.820192814 -0.014897343 0.911754668 0.286032319 0.294392645
1403637192988318976 0.909679294 1.328143239 -4.839832306 -0.014378462 0.912683368 0.282536328 0.294916183
1403637193038319104 0.934142828 1.319033980 -4.866328239 -0.011576444 0.912812650 0.281359017 0.295763642
1403637193088318976 0.955361366 1.298880696 -4.882617474 -0.005834531 0.911842406 0.284739554 0.295690387
1403637193138319104 0.976740599 1.290897489 -4.916427135 0.003834351 0.909244120 0.291751534 0.296886235
1403637193188318976 1.002682447 1.274168730 -4.937977791 0.014726832 0.906284690 0.299893200 0.297481567
1403637193238319104 1.029301167 1.255718946 -4.958602905 0.020919982 0.904354334 0.305528134 0.297250956
1403637193288318976 1.052241087 1.242336988 -4.990098953 0.025091974 0.902955353 0.309122503 0.297464818
1403637193338319104 1.072757959 1.232818842 -5.015287876 0.018512093 0.904474139 0.305319220 0.297260940
1403637193388318976 1.101613283 1.238126516 -5.054551125 0.012895946 0.906702042 0.299267590 0.296924174
1403637193438319104 1.124953508 1.222529173 -5.084585190 0.006035832 0.909035623 0.293278068 0.295982629
1403637193488318976 1.145279288 1.227676153 -5.119555473 0.000422081 0.910835028 0.287423402 0.296255291
1403637193538319104 1.172919154 1.226813316 -5.154373169 -0.004879410 0.912312508 0.283130407 0.295802712
1403637193588318976 1.195092559 1.227680683 -5.187452316 -0.009742348 0.912988186 0.280474395 0.296128064
1403637193638319104 1.228115916 1.220947742 -5.221699715 -0.013554066 0.913469732 0.278908789 0.295971632
1403637193688318976 1.254670024 1.213227510 -5.254739761 -0.015912874 0.913671374 0.278412253 0.295699209
1403637193738319104 1.283457160 1.206719637 -5.291702271 -0.019247634 0.913968027 0.276916444 0.295988500
1403637193788318976 1.313025475 1.197642326 -5.327550888 -0.020684004 0.914145648 0.276282728 0.295935392
1403637193838319104 1.340919137 1.192745447 -5.365132332 -0.022297608 0.914093018 0.275858939 0.296375781
1403637193888318976 1.378151655 1.175132275 -5.400078297 -0.022645926 0.914138019 0.276141703 0.295946896
1403637193938319104 1.412862062 1.163826227 -5.438385963 -0.021141913 0.914496005 0.274725795 0.296269804
1403637193988318976 1.448181629 1.157508612 -5.475419521 -0.019707089 0.915802598 0.270657182 0.296077579
1403637194038319104 1.478830338 1.157793641 -5.511236191 -0.016946591 0.916938126 0.266366303 0.296624690
1403637194088318976 1.518358946 1.154653072 -5.541417599 -0.015391557 0.917912781 0.263939768 0.295863062
1403637194138319104 1.553700447 1.165256858 -5.569406509 -0.014633062 0.918622971 0.261611134 0.295765668
1403637194188318976 1.591539979 1.166662931 -5.600699425 -0.013798635 0.918717980 0.261815906 0.295329094
1403637194238319104 1.634696245 1.173436999 -5.630091667 -0.013318694 0.917824745 0.264742702 0.295519352
1403637194288318976 1.666727066 1.179922938 -5.656162262 -0.012456737 0.917603195 0.265872151 0.295230746
1403637194338319104 1.716451168 1.184168577 -5.690278530 -0.013663729 0.916931212 0.268235147 0.295127779
1403637194388318976 1.752264261 1.188852549 -5.717932701 -0.013791041 0.916453540 0.269664913 0.295302480
1403637194438319104 1.794589162 1.185200334 -5.741600990 -0.015405660 0.916193247 0.270910442 0.294889927
1403637194488318976 1.842190981 1.188718557 -5.775548935 -0.013884973 0.916010022 0.271574944 0.294923425
1403637194538319104 1.884450078 1.187904358 -5.801637173 -0.014101582 0.915800035 0.272245735 0.294946820
1403637194588318976 1.927461624 1.183761716 -5.826106071 -0.014055640 0.915778518 0.272703439 0.294592768
1403637194638319104 1.974702358 1.175087690 -5.858937263 -0.014579372 0.915606439 0.273759544 0.294122279
1403637194688318976 2.019251347 1.171998858 -5.887485027 -0.015896663 0.914863408 0.276575983 0.293731064
1403637194738319104 2.063092232 1.165246487 -5.916840076 -0.016735757 0.913860619 0.280106932 0.293459982
1403637194788318976 2.114390850 1.152408838 -5.948099613 -0.017342525 0.913150311 0.282972395 0.292886257
1403637194838319104 2.157487154 1.148935318 -5.974689484 -0.016983796 0.912789583 0.284407467 0.292641699
1403637194888318976 2.214717865 1.140006542 -6.003935337 -0.017073149 0.912461042 0.286562145 0.291557014
1403637194938319104 2.261497498 1.135386705 -6.035037994 -0.013906825 0.912986159 0.284675241 0.291929543
1403637194988318976 2.338288784 1.126133204 -6.067780495 -0.012908767 0.914481044 0.281311512 0.290554076
1403637195038319104 2.365645409 1.133958220 -6.100461006 -0.010351472 0.916046381 0.275408596 0.291379422
1403637195088318976 2.411549330 1.142072201 -6.133238316 -0.007907913 0.917602181 0.269961774 0.291657954
1403637195138319104 2.470323801 1.137585998 -6.164510727 -0.006537081 0.919025183 0.266106814 0.290752679
1403637195188318976 2.536195278 1.133401275 -6.179687023 -0.005967333 0.920656025 0.261782467 0.289528579
1403637195238319104 2.589411736 1.135868907 -6.204938889 -0.005015649 0.921673477 0.258416891 0.289332896
1403637195288318976 2.641454458 1.147871733 -6.226309299 -0.004513070 0.922621191 0.254776031 0.289549559
1403637195338319104 2.711250305 1.149559021 -6.259208679 -0.002612693 0.923194885 0.253476530 0.288884014
1403637195388318976 2.754370689 1.158962965 -6.283756733 -0.003481708 0.923157692 0.252342463 0.289984584
1403637195438319104 2.813573599 1.162140489 -6.302771091 -0.002229210 0.923105001 0.251240492 0.291119218
1403637195488318976 2.870399237 1.168551922 -6.320225239 -0.002068395 0.922054768 0.251270294 0.294404447
1403637195538319104 2.917292595 1.177291274 -6.343608856 -0.001086408 0.920175135 0.252515525 0.299186260
1403637195588318976 2.960906982 1.178522110 -6.370775700 -0.001005201 0.918602645 0.252273738 0.304180980
1403637195638319104 3.021085739 1.172393203 -6.389791012 -0.001328595 0.917651653 0.251883000 0.307357520
1403637195688318976 3.080964088 1.169403553 -6.406948566 -0.001008780 0.917045951 0.250397772 0.310365319
1403637195738319104 3.125258684 1.164931536 -6.431619644 -0.001815771 0.916270375 0.248763159 0.313946098
1403637195788318976 3.179552794 1.154851913 -6.447453022 -0.004159085 0.915487230 0.249043941 0.315979242
1403637195838319104 3.231198311 1.149908662 -6.464294434 -0.008495641 0.916068196 0.244833112 0.317496002
1403637195888318976 3.278640985 1.146395922 -6.479311943 -0.014241247 0.916157782 0.242293045 0.318976790
1403637195938319104 3.313622952 1.136021495 -6.480457306 -0.020004563 0.916431069 0.239771187 0.319786847
1403637195988318976 3.372642994 1.121147156 -6.502353668 -0.027998041 0.916845679 0.237157166 0.319947749
1403637196038319104 3.423042774 1.120894432 -6.512979507 -0.034774996 0.917667329 0.232176304 0.320580035
1403637196088318976 3.485597610 1.113221169 -6.524934769 -0.041390549 0.919269681 0.225606441 0.319893479
1403637196138319104 3.541346073 1.109229207 -6.531622887 -0.046450913 0.921165049 0.217320830 0.319482356
1403637196188318976 3.583037853 1.096774817 -6.532085419 -0.050241906 0.923190713 0.207728878 0.319442332
1403637196238319104 3.653137207 1.097698212 -6.542035103 -0.052178897 0.925020933 0.199154466 0.319297820
1403637196288318976 3.700902700 1.094381452 -6.528701782 -0.052925847 0.926969230 0.190658912 0.318710089
1403637196338319104 3.750266552 1.088621736 -6.521093845 -0.054969151 0.928370357 0.184092373 0.318146080
1403637196388318976 3.806026936 1.088091969 -6.509635448 -0.055814579 0.929722607 0.178176582 0.317417264
1403637196438319104 3.878208160 1.080683112 -6.493141651 -0.056560367 0.930479288 0.175357252 0.316637069
1403637196488318976 3.936207533 1.074539781 -6.460834503 -0.054842651 0.930842400 0.175002620 0.316067815
1403637196538319104 4.005540848 1.063841581 -6.423648834 -0.054199141 0.931178987 0.176484570 0.314358592
1403637196588318976 4.063230991 1.068652630 -6.399796009 -0.049883895 0.931080163 0.176812470 0.315180361
1403637196638319104 4.128456593 1.064259171 -6.364303589 -0.047283068 0.930652261 0.180421457 0.314799607
1403637196688318976 4.188733101 1.055835724 -6.317984581 -0.043243252 0.930489838 0.183030725 0.314353943
1403637196738319104 4.255645275 1.046349883 -6.270120621 -0.039267730 0.930212021 0.185814187 0.314064920
1403637196788318976 4.320881844 1.051756382 -6.220142365 -0.034437638 0.929778039 0.188565284 0.314276963
1403637196838319104 4.388613224 1.046307683 -6.162655830 -0.034176342 0.929980040 0.189316660 0.313254416
1403637196888318976 4.445569515 1.042345881 -6.105935097 -0.034847766 0.930533111 0.186642393 0.313142747
1403637196938319104 4.518107891 1.044999719 -6.046275139 -0.031762466 0.930876553 0.186481997 0.312545121
1403637196988318976 4.578582287 1.031096816 -5.976992130 -0.023326255 0.930350661 0.189558178 0.313003570
1403637197038319104 4.653763771 1.028463960 -5.901639938 -0.016142646 0.929119408 0.192892760 0.315069735
1403637197088318976 4.716150284 1.014126301 -5.832042694 -0.011141133 0.926512361 0.197783470 0.319894314
1403637197138319104 4.783632755 0.999385715 -5.755169868 -0.007258237 0.923858464 0.201459408 0.325341254
1403637197188318976 4.832629204 0.985868335 -5.680469990 -0.004084551 0.919382274 0.206129700 0.335007578
1403637197238319104 4.901011467 0.973003983 -5.598335266 -0.001775253 0.915463924 0.208166420 0.344368130
1403637197288318976 4.970253944 0.948895454 -5.511218071 -0.001684418 0.910072088 0.213623226 0.355149299
1403637197338319104 5.019916058 0.932994246 -5.430434227 0.001142497 0.903505385 0.217279091 0.369413704
1403637197388318976 5.076249123 0.903278828 -5.348651886 0.001684970 0.896583736 0.219620615 0.384579748
1403637197438319104 5.128199100 0.877523422 -5.253441811 0.000377082 0.888867021 0.220119327 0.401824325
1403637197488318976 5.192389965 0.839928865 -5.155049801 -0.004688162 0.881161153 0.221268401 0.417819738
1403637197538319104 5.237629414 0.811756134 -5.074675560 -0.007475125 0.871749759 0.220119178 0.437657505
1403637197588318976 5.282192707 0.796254754 -4.995929718 -0.013140080 0.861214697 0.216687933 0.459546447
1403637197638319104 5.333315372 0.761847019 -4.899465561 -0.017238069 0.851212442 0.212564096 0.479537994
1403637197688318976 5.390338898 0.721698165 -4.807294846 -0.019329883 0.840776920 0.209655643 0.498763502
1403637197738319104 5.441657066 0.692191958 -4.729323864 -0.022654980 0.829981744 0.203433335 0.518875599
1403637197788318976 5.490684986 0.650521755 -4.636126518 -0.025664119 0.820117354 0.196079031 0.536937535
1403637197838319104 5.537626743 0.609136820 -4.535765648 -0.029792544 0.810911119 0.185751796 0.554104567
1403637197888318976 5.577294827 0.575635076 -4.472794056 -0.033092503 0.799353600 0.178325370 0.572833955
1403637197938319104 5.631731987 0.530237913 -4.366378784 -0.034678087 0.790308774 0.171804264 0.587105393
1403637197988318976 5.670405388 0.486636519 -4.289322376 -0.036651183 0.779816210 0.165132269 0.602722764
1403637198038319104 5.714974880 0.441033602 -4.196228981 -0.037705619 0.769988060 0.159543097 0.616638124
1403637198088318976 5.775388718 0.382671952 -4.081315994 -0.038409889 0.761950374 0.155426145 0.627534091
1403637198138319104 5.797966003 0.336547256 -3.985395908 -0.036988515 0.752689838 0.150957555 0.639766872
1403637198188318976 5.827081680 0.278485775 -3.884522438 -0.037349932 0.743356526 0.147273660 0.651411176
1403637198238319104 5.878376007 0.222099543 -3.795887947 -0.040051524 0.732989907 0.144332930 0.663543284
1403637198288318976 5.929481983 0.158335805 -3.697260618 -0.041073032 0.724186242 0.137739077 0.674459219
1403637198338319104 5.962820530 0.107864380 -3.608467817 -0.040866002 0.714736938 0.132934228 0.685426533
1403637198388318976 5.989440918 0.013922930 -3.478518724 -0.043441586 0.709085047 0.126563042 0.692309976
1403637198438319104 6.030601025 -0.024099231 -3.397893906 -0.043236174 0.701669633 0.117604405 0.701398313
1403637198488318976 6.061280727 -0.080134749 -3.298378706 -0.043747470 0.696828842 0.111772321 0.707122803
1403637198538319104 6.101323128 -0.120549202 -3.190384626 -0.044685017 0.693797827 0.103466578 0.711296320
1403637198588318976 6.120245934 -0.155417800 -3.101071835 -0.044324432 0.690669239 0.096886061 0.715279281
1403637198638319104 6.145861626 -0.221168280 -2.960704327 -0.046493709 0.690692604 0.093357399 0.715588152
1403637198688318976 6.170933723 -0.264898062 -2.832525730 -0.046200275 0.689854801 0.091509424 0.716653287
1403637198738319104 6.204643250 -0.296674371 -2.727878332 -0.044459321 0.688090146 0.091659024 0.718438566
1403637198788318976 6.226976395 -0.335658193 -2.596823215 -0.042617787 0.688256919 0.090933368 0.718482673
1403637198838319104 6.251922607 -0.358818293 -2.495822668 -0.036197178 0.686743081 0.088852383 0.720540702
1403637198888318976 6.271464348 -0.386734724 -2.357645512 -0.029864218 0.687538743 0.086591192 0.720347524
1403637198938319104 6.285875797 -0.408130527 -2.244094610 -0.019693863 0.685944140 0.088350803 0.722002089
1403637198988318976 6.300195217 -0.426177979 -2.111282825 -0.007794446 0.684347928 0.089799799 0.723562777
1403637199038319104 6.313678265 -0.466095984 -1.960277677 -0.000095635 0.682202280 0.094470747 0.725034654
1403637199088318976 6.323077202 -0.519646704 -1.813519001 0.002721805 0.678109229 0.101162709 0.727960587
1403637199138319104 6.317553043 -0.523700833 -1.697576046 0.006763940 0.671523809 0.104329258 0.733570337
1403637199188318976 6.302783012 -0.545738697 -1.577039838 0.008161621 0.664680064 0.108052604 0.739228308
1403637199238319104 6.306750774 -0.580386758 -1.435701847 0.008128180 0.657590806 0.110361233 0.745203793
1403637199288318976 6.292140007 -0.614663243 -1.304151297 0.007043072 0.650389016 0.108718500 0.751747787
1403637199338319104 6.276875496 -0.649850547 -1.156631827 0.008130355 0.642979801 0.105587989 0.758526266
1403637199388318976 6.262658596 -0.688838065 -1.029086709 0.006726064 0.634217978 0.101161458 0.766478121
1403637199438319104 6.235668182 -0.720599294 -0.910687447 0.007270686 0.623419702 0.096795864 0.775838614
1403637199488318976 6.232082844 -0.767314136 -0.753302574 0.006448950 0.614950120 0.092289880 0.783120215
1403637199538319104 6.199034691 -0.805986345 -0.626792789 0.006078440 0.603773415 0.088994332 0.792149425
1403637199588318976 6.175011635 -0.838657975 -0.496661067 0.007101937 0.592438340 0.085070357 0.801080108
1403637199638319104 6.142263412 -0.871580005 -0.361288428 0.011458139 0.581056595 0.083597474 0.809477210
1403637199688318976 6.107645035 -0.906282961 -0.235865235 0.016219378 0.567887843 0.082278326 0.818822682
1403637199738319104 6.082088947 -0.924846232 -0.110134125 0.021847952 0.553865850 0.081985116 0.828271508
1403637199788318976 6.049291134 -0.961394370 0.020588160 0.027454840 0.537920237 0.084524371 0.838298082
1403637199838319104 6.003852844 -0.973411798 0.126931667 0.035814762 0.519547522 0.085255191 0.849422932
1403637199888318976 5.959899902 -0.975987315 0.279792309 0.048126832 0.503614187 0.087744601 0.858112693
1403637199938319104 5.927921772 -0.964862943 0.385115862 0.059938289 0.482044369 0.088394620 0.869613171
1403637199988318976 5.881146431 -0.970963359 0.494605064 0.072370879 0.461445600 0.087411895 0.879880428
1403637200038319104 5.820187092 -0.967157483 0.615998983 0.083930627 0.442404717 0.086712658 0.888658881
1403637200088318976 5.752736568 -0.940627277 0.774950027 0.095859714 0.427464932 0.079930782 0.895374596
1403637200138319104 5.698294640 -0.986722887 0.922474861 0.095500961 0.413082212 0.074595854 0.902595222
1403637200188318976 5.633472443 -0.973073840 1.041037083 0.093272723 0.397099763 0.067271538 0.910541892
1403637200238319104 5.565624237 -0.951678038 1.104185104 0.089508295 0.377653986 0.061900582 0.919529259
1403637200288318976 5.509431839 -0.948150575 1.183857203 0.076250173 0.364308000 0.052477136 0.926667035
1403637200338319104 5.448949814 -0.923302054 1.284012556 0.060258377 0.355299413 0.043406028 0.931797862
1403637200388318976 5.393486500 -0.925890207 1.360627413 0.041913003 0.345235854 0.040113505 0.936721087
1403637200438319104 5.338184357 -0.913680077 1.438411951 0.026057307 0.336943090 0.040293198 0.940301478
1403637200488318976 5.262155533 -0.883376956 1.526898503 0.012147416 0.332880825 0.036594927 0.942180216
1403637200538319104 5.191389084 -0.873437047 1.596275926 0.004360897 0.325880021 0.042430285 0.944448411
1403637200588318976 5.126317024 -0.859730244 1.660897136 0.002541103 0.319560707 0.047899432 0.946350932
1403637200638319104 5.046452999 -0.848697484 1.730614066 -0.000268961 0.316598713 0.051549923 0.947157741
1403637200688318976 4.979324341 -0.845147371 1.789233565 -0.000702128 0.314370126 0.056180533 0.947636366
1403637200738319104 4.908439636 -0.836502194 1.853378892 -0.001826448 0.313739002 0.059401948 0.947647572
1403637200788318976 4.838454723 -0.843631089 1.907505751 0.000528885 0.313719124 0.066213734 0.947204173
1403637200838319104 4.778979301 -0.841202676 1.959160209 0.004329068 0.315125912 0.071528591 0.946340621
1403637200888318976 4.698588848 -0.839661717 2.012454271 0.006727738 0.318952084 0.074804068 0.944790244
1403637200938319104 4.629110813 -0.836431921 2.062259912 0.007238006 0.323406100 0.075999752 0.943175554
1403637200988318976 4.559082031 -0.844713092 2.103821039 0.006611594 0.327777833 0.078254402 0.941485107
1403637201038319104 4.497655869 -0.845038056 2.143270969 0.006988991 0.332435369 0.078424804 0.939833701
1403637201088318976 4.430013180 -0.850096405 2.179780722 0.006279253 0.336869776 0.079557084 0.938163102
1403637201138319104 4.361532688 -0.855357111 2.217425823 0.004782027 0.342048675 0.079829931 0.936272979
1403637201188318976 4.303078651 -0.864400506 2.249094486 0.004866247 0.345132887 0.082132027 0.934940577
1403637201238319104 4.235930443 -0.869921505 2.279613972 0.003879365 0.347848028 0.085954629 0.933594406
1403637201288318976 4.169393539 -0.883667588 2.307152748 0.005131460 0.349959552 0.094438873 0.931978166
1403637201338319104 4.094058514 -0.885457516 2.332222462 0.008195052 0.352252632 0.106201693 0.929823697
1403637201388318976 4.028108120 -0.892387867 2.352996111 0.008484214 0.355148971 0.118544951 0.927223980
1403637201438319104 3.979411364 -0.900266647 2.375570774 0.007926770 0.357892096 0.132265985 0.924313843
1403637201488318976 3.919774055 -0.898471832 2.395176649 0.007264914 0.361843735 0.144792840 0.920897067
1403637201538319104 3.859933853 -0.902693987 2.405894995 0.006835436 0.365668207 0.156591982 0.917452455
1403637201588318976 3.809414387 -0.899472237 2.423165083 0.007186594 0.369328767 0.165068716 0.914492726
1403637201638319104 3.760183573 -0.896035612 2.429221630 0.008816903 0.372239560 0.172880813 0.911850929
1403637201688318976 3.713970184 -0.891762197 2.437399864 0.011286503 0.376104504 0.176762834 0.909490466
1403637201738319104 3.677517891 -0.883728266 2.434554100 0.013818460 0.380615324 0.173845291 0.908140361
1403637201788318976 3.629251242 -0.875931680 2.440556765 0.014820346 0.386728525 0.167670116 0.906701803
1403637201838319104 3.605779648 -0.868571043 2.435254574 0.015728302 0.389939040 0.163825855 0.906013966
1403637201888318976 3.560151577 -0.859301686 2.425954580 0.016646482 0.393374056 0.160129800 0.905173004
1403637201938319104 3.535023928 -0.853633881 2.412882805 0.016395481 0.394906282 0.158245653 0.904841721
1403637201988318976 3.509266853 -0.850090981 2.394550800 0.014357170 0.394170612 0.160547405 0.904791653
1403637202038319104 3.476572752 -0.841120780 2.377485275 0.012096627 0.392741948 0.165307671 0.904588759
1403637202088318976 3.455313683 -0.839939952 2.353968382 0.007508929 0.389815301 0.171750069 0.904704154
1403637202138319104 3.433128834 -0.835033894 2.326515198 0.000447534 0.387335718 0.176057532 0.904972136
1403637202188318976 3.417483807 -0.829717100 2.293961763 -0.008239790 0.386670738 0.174999550 0.905424178
1403637202238319104 3.408671856 -0.826123357 2.262042284 -0.018406840 0.388694525 0.167241842 0.905874133
1403637202288318976 3.393966198 -0.819657385 2.229992390 -0.029872056 0.391694635 0.156450912 0.906204224
1403637202338319104 3.394623280 -0.812339902 2.192643166 -0.038906835 0.393481374 0.147808298 0.906538129
1403637202388318976 3.392296791 -0.802964509 2.156686544 -0.045742545 0.395439148 0.139421821 0.906695664
1403637202438319104 3.394019604 -0.796567798 2.116012335 -0.049307469 0.396603703 0.133292690 0.906921923
1403637202488318976 3.396187305 -0.789918125 2.085406303 -0.048572183 0.397804499 0.128424883 0.907137990
1403637202538319104 3.397849083 -0.783163011 2.050122738 -0.046200197 0.398837358 0.124338992 0.907377601
1403637202588318976 3.406461716 -0.776034236 2.014270544 -0.041258540 0.398884803 0.122029066 0.907908320
1403637202638319104 3.403496265 -0.773247004 1.979959011 -0.036084451 0.400189728 0.117916353 0.908097923
1403637202688318976 3.422069311 -0.770148695 1.944785237 -0.032520320 0.400750250 0.114167884 0.908464313
1403637202738319104 3.439006090 -0.770281911 1.910962582 -0.028884742 0.401437670 0.109826341 0.908818841
1403637202788318976 3.451724529 -0.772569776 1.875090957 -0.028890047 0.402984351 0.103878357 0.908833504
1403637202838319104 3.471174240 -0.775567770 1.839959621 -0.029515898 0.404718578 0.097969145 0.908698916
1403637202888318976 3.477727413 -0.772860587 1.802681446 -0.030937148 0.406616449 0.092410892 0.908386588
1403637202938319104 3.494917393 -0.770041466 1.770693421 -0.032179717 0.408165425 0.087559782 0.908129275
1403637202988318976 3.502813339 -0.762686372 1.740052342 -0.033111718 0.409797400 0.083987705 0.907698035
1403637203038319104 3.519304752 -0.761909127 1.704818368 -0.033700265 0.410410225 0.082323484 0.907552004
1403637203088318976 3.536721230 -0.755411506 1.676604509 -0.033718362 0.410621405 0.081368767 0.907541871
1403637203138319104 3.542047024 -0.750323474 1.647627473 -0.032240093 0.410676062 0.082844980 0.907437325
1403637203188318976 3.559252024 -0.745388389 1.611954451 -0.033433154 0.411150187 0.081586674 0.907293439
1403637203238319104 3.574780941 -0.740329623 1.586059093 -0.032442931 0.411783397 0.081330128 0.907065213
1403637203288318976 3.584826469 -0.728599906 1.555717707 -0.032340605 0.412407339 0.079853959 0.906916559
1403637203338319104 3.606569290 -0.722929060 1.530182958 -0.032030951 0.412449479 0.079864956 0.906907439
1403637203388318976 3.610888958 -0.712377191 1.504599810 -0.031453252 0.412613600 0.080321819 0.906812608
1403637203438319104 3.621528149 -0.703844786 1.479322314 -0.032129016 0.413292021 0.079575628 0.906545699
1403637203488318976 3.636895180 -0.692440450 1.454878926 -0.032031056 0.413279682 0.079655252 0.906547844
1403637203538319104 3.647560835 -0.684754848 1.428402185 -0.031747874 0.413683206 0.079109699 0.906421483
1403637203588318976 3.654667854 -0.666762650 1.406659126 -0.031462722 0.414646685 0.077123538 0.906162322
1403637203638319104 3.661556959 -0.656229675 1.389173508 -0.032132950 0.415973425 0.075175583 0.905694306
1403637203688318976 3.674770117 -0.642798245 1.370383382 -0.031844378 0.415967673 0.075506352 0.905679643
1403637203738319104 3.687112331 -0.638029814 1.351515770 -0.031176928 0.416260540 0.076072410 0.905520916
1403637203788318976 3.687757015 -0.621713698 1.334279060 -0.030733895 0.416824132 0.076373011 0.905251503
1403637203838319104 3.694652796 -0.604218483 1.315024614 -0.030309208 0.416852742 0.076815568 0.905215204
1403637203888318976 3.695775270 -0.587564886 1.304036260 -0.029785536 0.417797118 0.076215349 0.904847860
1403637203938319104 3.714816809 -0.575891316 1.285296202 -0.029558029 0.417378902 0.076290131 0.905041933
1403637203988318976 3.717413187 -0.555829883 1.272265911 -0.029761478 0.417851388 0.076046981 0.904837728
1403637204038319104 3.720886230 -0.538497031 1.258216619 -0.030244857 0.418584853 0.075310953 0.904544175
1403637204088318976 3.720222712 -0.517467558 1.243964195 -0.029561035 0.418681055 0.076046444 0.904460788
1403637204138319104 3.728506088 -0.509948134 1.231882572 -0.029987814 0.418786168 0.075952277 0.904405951
1403637204188318976 3.734841347 -0.494078875 1.213089705 -0.030197643 0.418450385 0.076518185 0.904506683
1403637204238319104 3.733026743 -0.486195862 1.203385711 -0.030413743 0.419075280 0.075851515 0.904266238
1403637204288318976 3.730635643 -0.480441272 1.190912962 -0.031327628 0.419180691 0.077329181 0.904061019
1403637204338319104 3.730144739 -0.475603342 1.178333521 -0.030221924 0.418871820 0.078620620 0.904130459
1403637204388318976 3.730947495 -0.472315222 1.165349603 -0.027587263 0.418569624 0.080903456 0.904153228
1403637204438319104 3.719949961 -0.470545024 1.156904936 -0.025340024 0.419974774 0.080188185 0.903630972
1403637204488318976 3.724426746 -0.469029456 1.142006516 -0.020443831 0.419492722 0.081918418 0.903823674
1403637204538319104 3.722378731 -0.471292347 1.126635551 -0.018513845 0.420201093 0.082412340 0.903491259
1403637204588318976 3.721198559 -0.479471773 1.113754392 -0.018898228 0.420966238 0.083801374 0.902999222
1403637204638319104 3.712304831 -0.486603886 1.103325725 -0.019905446 0.422315121 0.084861055 0.902248442
1403637204688318976 3.707169771 -0.491297603 1.088207603 -0.022042541 0.423617661 0.083616994 0.901704133
1403637204738319104 3.706588745 -0.496724963 1.072377086 -0.022329772 0.424189746 0.084594786 0.901336908
1403637204788318976 3.697914600 -0.500858068 1.058689117 -0.024215428 0.425276250 0.085161604 0.900722623
1403637204838319104 3.695322275 -0.514650226 1.046412468 -0.025878713 0.425409704 0.087505832 0.900388598
1403637204888318976 3.690428495 -0.511546850 1.034384251 -0.027065065 0.426391453 0.086986952 0.899939477
1403637204938319104 3.680419683 -0.505916417 1.026354790 -0.028750286 0.427058369 0.087191932 0.899551094
1403637204988318976 3.675643444 -0.504852414 1.007864952 -0.031903964 0.426576138 0.089041725 0.899492383
1403637205038319104 3.662970543 -0.505062819 1.002944708 -0.035089225 0.426915258 0.090353817 0.899081945
1403637205088318976 3.662654877 -0.498260289 0.994602919 -0.037066203 0.426750779 0.090607427 0.899055183
1403637205138319104 3.654664516 -0.494222164 0.983440161 -0.037260313 0.426693738 0.091360122 0.898998022
1403637205188318976 3.652358532 -0.494351119 0.977771878 -0.037831519 0.426595241 0.090826422 0.899075031
1403637205238319104 3.641460896 -0.483817905 0.969929576 -0.038499817 0.425146967 0.090525210 0.899762750
1403637205288318976 3.637162685 -0.479244053 0.967124939 -0.039513137 0.422815561 0.089889094 0.900880516
1403637205338319104 3.633318901 -0.471594781 0.961847663 -0.038933348 0.419449180 0.087799653 0.902683675
1403637205388318976 3.623647213 -0.471412718 0.951812506 -0.039472107 0.416314930 0.086112291 0.904272377
1403637205438319104 3.617728472 -0.468375921 0.952356458 -0.038939714 0.413857073 0.083414279 0.905675530
1403637205488318976 3.610612869 -0.465420067 0.948618293 -0.036579348 0.411146611 0.080866233 0.907238126
1403637205538319104 3.606057644 -0.468830138 0.946955562 -0.034136508 0.408531874 0.078487977 0.908722222
1403637205588318976 3.597666502 -0.471277475 0.941973925 -0.032945253 0.406660229 0.076430663 0.909780443
1403637205638319104 3.596891165 -0.470801055 0.943022490 -0.031364195 0.404472411 0.075378917 0.910898685
1403637205688318976 3.586272717 -0.466780007 0.940699697 -0.031221649 0.403189212 0.073740825 0.911606252
1403637205738319104 3.578702688 -0.460603029 0.940809250 -0.031200007 0.401754022 0.074050680 0.912215352
1403637205788318976 3.569500446 -0.460398853 0.945114255 -0.031200685 0.401103467 0.073955089 0.912509263
1403637205838319104 3.567464828 -0.449832141 0.943327665 -0.031574599 0.400222570 0.073005147 0.912959576
1403637205888318976 3.557103872 -0.446500033 0.944732785 -0.031600334 0.399431556 0.073972329 0.913227201
1403637205938319104 3.545270920 -0.431603670 0.945576191 -0.030919658 0.399098992 0.073445827 0.913438380
1403637205988318976 3.535787821 -0.429324836 0.949356437 -0.030771187 0.398865581 0.073155195 0.913568676
1403637206038319104 3.529319763 -0.420689464 0.953473091 -0.029999312 0.398186386 0.073336408 0.913876057
1403637206088318976 3.516795397 -0.419848830 0.956445098 -0.029309578 0.397657394 0.075010858 0.913992882
1403637206138319104 3.505961418 -0.418685645 0.957273245 -0.028111998 0.396286041 0.078056283 0.914371014
1403637206188318976 3.496479511 -0.423769236 0.955528736 -0.026121808 0.394266486 0.082758822 0.914889336
1403637206238319104 3.484451056 -0.416301042 0.958381295 -0.024746619 0.393285632 0.084516242 0.915189087
1403637206288318976 3.472488642 -0.427611172 0.960888028 -0.023434849 0.392871112 0.086576760 0.915209055
1403637206338319104 3.458579302 -0.429677010 0.960647106 -0.021822199 0.392724514 0.087731719 0.915201843
1403637206388318976 3.450389385 -0.438105702 0.959367990 -0.021743668 0.392455667 0.088022426 0.915291071
1403637206438319104 3.439215660 -0.446524352 0.959097028 -0.021875745 0.392686188 0.088131465 0.915178597
1403637206488318976 3.425813198 -0.457028031 0.961466551 -0.022134727 0.393075764 0.087607011 0.915055454
1403637206538319104 3.414506912 -0.464100242 0.953341365 -0.021587199 0.393252283 0.087545514 0.914998591
1403637206588318976 3.406114578 -0.474569261 0.955433249 -0.022047469 0.393929243 0.086987726 0.914749563
1403637206638319104 3.395258904 -0.482780963 0.952532053 -0.022486711 0.394413382 0.086399138 0.914586008
1403637206688318976 3.383220196 -0.487545460 0.947539806 -0.023037031 0.395272106 0.085222818 0.914311945
1403637206738319104 3.373578548 -0.489131600 0.947097898 -0.022784026 0.395917773 0.084156834 0.914137661
1403637206788318976 3.357232571 -0.488472134 0.943060279 -0.022075409 0.396734178 0.082883425 0.913917422
1403637206838319104 3.348405361 -0.492501557 0.947545886 -0.022346616 0.397536695 0.082678042 0.913580596
1403637206888318976 3.342455864 -0.493040830 0.938980103 -0.021405382 0.397721529 0.082076982 0.913576901
1403637206938319104 3.329296350 -0.493605942 0.940333843 -0.019539105 0.398067206 0.081750512 0.913497448
1403637206988318976 3.314553261 -0.498946339 0.934631944 -0.019395988 0.398530692 0.081715778 0.913301528
1403637207038319104 3.310156345 -0.506685078 0.926458955 -0.018925944 0.398576200 0.081997119 0.913266301
1403637207088318976 3.290862799 -0.508522034 0.927300215 -0.019419247 0.399454594 0.082243949 0.912849844
1403637207138319104 3.278886557 -0.513902545 0.919862390 -0.018058518 0.400059938 0.082308680 0.912606835
1403637207188318976 3.271984100 -0.515514851 0.916916013 -0.017913105 0.400492758 0.082816415 0.912373841
1403637207238319104 3.255769253 -0.514848351 0.910178661 -0.015960386 0.401072472 0.082702823 0.912165761
1403637207288318976 3.243874073 -0.516001523 0.904656529 -0.016437855 0.401433945 0.083515525 0.911924183
1403637207338319104 3.227252960 -0.514928818 0.905557632 -0.016972104 0.402349502 0.084051348 0.911461532
1403637207388318976 3.213826895 -0.512067258 0.898757219 -0.017225470 0.402497798 0.083993047 0.911396742
1403637207438319104 3.199423075 -0.500021458 0.895631433 -0.016854260 0.403093666 0.083647400 0.911172092
1403637207488318976 3.180695295 -0.490653962 0.888623476 -0.017207842 0.403569788 0.084291920 0.910895228
1403637207538319104 3.168903589 -0.486948490 0.885674477 -0.018935082 0.403574944 0.086398840 0.910661280
1403637207588318976 3.149857521 -0.472195596 0.881669521 -0.020760143 0.402854979 0.090974443 0.910494685
1403637207638319104 3.135985851 -0.467324436 0.874127746 -0.025284920 0.400729030 0.098567463 0.910528064
1403637207688318976 3.118703604 -0.458734393 0.866771102 -0.028718751 0.399340898 0.103797175 0.910454929
1403637207738319104 3.106624842 -0.454739362 0.860246539 -0.030891156 0.399079382 0.106130011 0.910229564
1403637207788318976 3.086646080 -0.448498845 0.858694792 -0.031124854 0.400145680 0.104613572 0.909928918
1403637207838319104 3.081417561 -0.444695711 0.847439408 -0.030900937 0.401103407 0.101593442 0.909857094
1403637207888318976 3.068347454 -0.449957997 0.839066863 -0.030887200 0.402585894 0.098354317 0.909558713
1403637207938319104 3.061769485 -0.454403728 0.829479575 -0.030100387 0.403713226 0.095067151 0.909434915
1403637207988318976 3.046257496 -0.464569151 0.815178394 -0.029802391 0.404695094 0.092713483 0.909251273
1403637208038319104 3.033683538 -0.471085131 0.805444717 -0.029591631 0.405935436 0.090183370 0.908959687
1403637208088318976 3.027776718 -0.485191941 0.795516014 -0.030348001 0.406541258 0.088704459 0.908809483
1403637208138319104 3.012969494 -0.488415807 0.784780145 -0.030385735 0.407425284 0.087236755 0.908554435
1403637208188318976 3.005241871 -0.503028810 0.771606207 -0.029890396 0.408166617 0.085395120 0.908413053
1403637208238319104 2.996145725 -0.515855551 0.760030627 -0.030916128 0.408475339 0.085980706 0.908184648
1403637208288318976 2.982833385 -0.530982792 0.754496932 -0.029126003 0.407982886 0.090234019 0.908052564
1403637208338319104 2.973641396 -0.535618246 0.738964200 -0.025816143 0.406791240 0.094507635 0.908252537
1403637208388318976 2.968765736 -0.546661854 0.730416059 -0.023915542 0.406338453 0.097573519 0.908183098
1403637208438319104 2.961533546 -0.550704718 0.721260548 -0.022190310 0.406952620 0.097980767 0.907907963
1403637208488318976 2.955765009 -0.556053400 0.714122653 -0.022314949 0.407481432 0.097551242 0.907714009
1403637208538319104 2.953315735 -0.564665556 0.698342085 -0.021638375 0.407844484 0.096610039 0.907667994
1403637208588318976 2.939439774 -0.560381413 0.693141341 -0.022438141 0.409551561 0.093633264 0.907191753
1403637208638319104 2.933103323 -0.562367499 0.679077983 -0.022908388 0.410090446 0.091834061 0.907120466
1403637208688318976 2.922538280 -0.559814453 0.672996521 -0.023325499 0.411374450 0.088902250 0.906820476
1403637208738319104 2.912484169 -0.552546501 0.666894197 -0.022313375 0.412003994 0.087410748 0.906705141
1403637208788318976 2.908410072 -0.550759315 0.656733036 -0.021758197 0.412206501 0.086483546 0.906715453
1403637208838319104 2.906195879 -0.547574520 0.650441527 -0.021854699 0.412582844 0.085691191 0.906617224
1403637208888318976 2.892671347 -0.543722987 0.636475563 -0.023252225 0.413156748 0.084140278 0.906466365
1403637208938319104 2.882510662 -0.530215740 0.635649681 -0.025178079 0.415123641 0.078906730 0.905986845
1403637208988318976 2.878460169 -0.522522509 0.619620442 -0.028422697 0.416733265 0.073539712 0.905603349
1403637209038319104 2.871018648 -0.507126570 0.615427613 -0.031307157 0.418766677 0.067311220 0.905054450
1403637209088318976 2.859789133 -0.498497993 0.612691104 -0.034195717 0.419820279 0.062102083 0.904834211
1403637209138319104 2.857056141 -0.491113842 0.605924964 -0.034682576 0.418207437 0.058538090 0.905799627
1403637209188318976 2.839944839 -0.473453104 0.600076199 -0.035173256 0.412716955 0.059644334 0.908223629
1403637209238319104 2.823274136 -0.466599852 0.604829550 -0.034299534 0.405216992 0.063936628 0.911336839
1403637209288318976 2.799301624 -0.458000600 0.601225376 -0.036014087 0.396868765 0.067856394 0.914654970
1403637209338319104 2.787486076 -0.456976026 0.602604747 -0.038034637 0.388843775 0.071106903 0.917767763
1403637209388318976 2.767424583 -0.452044576 0.599583983 -0.041355830 0.382223308 0.072382823 0.920301974
1403637209438319104 2.752755165 -0.453899652 0.594619751 -0.045658555 0.376378387 0.073367491 0.922427177
1403637209488318976 2.736572266 -0.449318945 0.602347314 -0.051938660 0.371442974 0.074268579 0.924022019
1403637209538319104 2.726095915 -0.459401041 0.590445817 -0.060634028 0.366018414 0.076043643 0.925511420
1403637209588318976 2.708144665 -0.460433513 0.586891353 -0.070005335 0.361790806 0.077365823 0.926402271
1403637209638319104 2.695688248 -0.469720066 0.592190385 -0.078410722 0.357960373 0.079432301 0.927041888
1403637209688318976 2.682318211 -0.474816293 0.596995652 -0.084145553 0.355060756 0.080592975 0.927553833
1403637209738319104 2.667932034 -0.492105126 0.597722411 -0.088738978 0.352321297 0.082548663 0.927998245
1403637209788318976 2.665470839 -0.500598729 0.612374425 -0.091349013 0.351119369 0.082635313 0.928192854
1403637209838319104 2.660032511 -0.517682672 0.618498921 -0.094013147 0.349937141 0.083193108 0.928323448
1403637209888318976 2.654963017 -0.527142227 0.634843290 -0.096098706 0.348915130 0.085590057 0.928276658
1403637209938319104 2.653119802 -0.538388014 0.645964086 -0.099460863 0.347974390 0.087726310 0.928076208
1403637209988318976 2.649743557 -0.551723897 0.669848144 -0.104778349 0.347688735 0.089123972 0.927464783
1403637210038319104 2.664940357 -0.557069004 0.690275252 -0.110827468 0.346644044 0.090959057 0.926974475
1403637210088318976 2.659392834 -0.555605888 0.715570927 -0.116590008 0.346774727 0.092323333 0.926083386
1403637210138319104 2.664151669 -0.553789556 0.749602616 -0.121766113 0.346185267 0.095529795 0.925312281
1403637210188318976 2.677578926 -0.556963265 0.779693067 -0.128309011 0.345265806 0.097769804 0.924537361
1403637210238319104 2.689229965 -0.549646854 0.817781210 -0.133118063 0.344777077 0.100027367 0.923798084
1403637210288318976 2.701703310 -0.546522558 0.863424063 -0.137665018 0.344638348 0.101138644 0.923062146
1403637210338319104 2.716459751 -0.544461668 0.910338998 -0.139756918 0.344420284 0.102265716 0.922704935
1403637210388318976 2.745877028 -0.545040548 0.949976444 -0.141542032 0.343270123 0.103712134 0.922699988
1403637210438319104 2.764125347 -0.540290773 1.011873603 -0.139731124 0.343946218 0.102527909 0.922856569
1403637210488318976 2.795925617 -0.546718776 1.067164302 -0.134498864 0.344263792 0.099630989 0.923832357
1403637210538319104 2.825383663 -0.550564349 1.131173730 -0.126592025 0.345331848 0.096553534 0.924877167
1403637210588318976 2.862172127 -0.563518405 1.194642305 -0.119551927 0.345409125 0.095071867 0.925938070
1403637210638319104 2.892813683 -0.559659719 1.263670921 -0.111428365 0.345687687 0.093131483 0.927043855
1403637210688318976 2.932315826 -0.567155838 1.340498090 -0.105754845 0.345736831 0.091271497 0.927874684
1403637210738319104 2.970683336 -0.576689661 1.412433505 -0.101549812 0.345239282 0.091387518 0.928518057
1403637210788318976 3.007472515 -0.590379238 1.483508825 -0.096761510 0.343455791 0.095394850 0.929287434
1403637210838319104 3.047695398 -0.595307291 1.567974687 -0.091545157 0.342462450 0.098269068 0.929882884
1403637210888318976 3.103689194 -0.595856965 1.648213863 -0.085369281 0.340742499 0.102359287 0.930660665
1403637210938319104 3.150850773 -0.599747002 1.733075380 -0.076658696 0.339667797 0.105447605 0.931466639
1403637210988318976 3.199301243 -0.607905924 1.815358877 -0.068023197 0.339358449 0.106992297 0.932073653
1403637211038319104 3.254587412 -0.613749146 1.897781610 -0.059327353 0.339074463 0.108102627 0.932642817
1403637211088318976 3.304708004 -0.616504431 1.983413696 -0.051271237 0.339286029 0.109780140 0.932847559
1403637211138319104 3.357465982 -0.618517995 2.069700241 -0.047835946 0.340706974 0.107948013 0.932725966
1403637211188318976 3.421726227 -0.616285324 2.150998831 -0.045745444 0.342999458 0.102610625 0.932593048
1403637211238319104 3.476573944 -0.618792117 2.233150959 -0.042393874 0.345636904 0.097629845 0.932312310
1403637211288318976 3.538599730 -0.619182408 2.314226389 -0.038212094 0.348742366 0.092077352 0.931901455
1403637211338319104 3.600181580 -0.621375740 2.396548510 -0.033957552 0.351723731 0.087657310 0.931371868
1403637211388318976 3.658424854 -0.618852735 2.478090286 -0.029529540 0.353958249 0.084196799 0.930995405
1403637211438319104 3.723936081 -0.624381781 2.556196928 -0.028193051 0.355371296 0.082858481 0.930618525
1403637211488318976 3.781035423 -0.614970684 2.638365984 -0.026366372 0.356339931 0.082041495 0.930374086
1403637211538319104 3.836451769 -0.611064553 2.718004704 -0.028227001 0.356405437 0.083651282 0.930150986
1403637211588318976 3.893492937 -0.607342064 2.794075966 -0.030767905 0.356403530 0.085516118 0.929901540
1403637211638319104 3.958628178 -0.605319977 2.872424126 -0.032975171 0.355736256 0.087683193 0.929879606
1403637211688318976 4.014890671 -0.609008253 2.944677830 -0.034257095 0.354901046 0.090405069 0.929891706
1403637211738319104 4.076764584 -0.608578146 3.018961668 -0.038787045 0.353204638 0.095256820 0.929875374
1403637211788318976 4.132719040 -0.613217890 3.090097427 -0.042573724 0.351179898 0.101496711 0.929816425
1403637211838319104 4.195481300 -0.618825495 3.160839558 -0.045182861 0.348861188 0.108674273 0.929754972
1403637211888318976 4.253680229 -0.625900209 3.230554819 -0.047886863 0.348220915 0.111607492 0.929512143
1403637211938319104 4.318323612 -0.636776984 3.301247120 -0.049669560 0.348840266 0.110899605 0.929271042
1403637211988318976 4.385809898 -0.649685502 3.367920399 -0.049138743 0.349764496 0.107620351 0.929337382
1403637212038319104 4.459982872 -0.664026618 3.434938431 -0.046375409 0.351851285 0.101820424 0.929345250
1403637212088318976 4.521955490 -0.680278480 3.503194809 -0.039896347 0.354418963 0.095611043 0.929329872
1403637212138319104 4.594020844 -0.694343567 3.565163612 -0.032245707 0.355994791 0.090087421 0.929576337
1403637212188318976 4.655140877 -0.720035017 3.634574413 -0.026564918 0.358333498 0.085277826 0.929311097
1403637212238319104 4.725608826 -0.740569949 3.699560642 -0.021591879 0.359496832 0.082286522 0.929260314
1403637212288318976 4.792554855 -0.763393342 3.763138294 -0.019105336 0.360448897 0.079999678 0.929145634
1403637212338319104 4.859414101 -0.786613524 3.821898937 -0.016279830 0.361271113 0.078519121 0.929006398
1403637212388318976 4.922576427 -0.809896648 3.879365921 -0.014897614 0.362159371 0.077895358 0.928736210
1403637212438319104 4.986297131 -0.837888420 3.937707901 -0.014503703 0.363201499 0.076869994 0.928420842
1403637212488318976 5.048641205 -0.862146974 3.992728233 -0.016836578 0.363767445 0.077570282 0.928101659
1403637212538319104 5.108255386 -0.891266584 4.046608925 -0.021230640 0.364376098 0.078581505 0.927687585
1403637212588318976 5.166712284 -0.916950643 4.099484921 -0.025359068 0.364726275 0.080564149 0.927276134
1403637212638319104 5.229752541 -0.945922673 4.152042866 -0.030978318 0.365158588 0.082494348 0.926765442
1403637212688318976 5.288176060 -0.969577909 4.204089165 -0.035144821 0.365102530 0.083811544 0.926520705
1403637212738319104 5.348541260 -0.998894393 4.253597736 -0.039059173 0.365617692 0.083366066 0.926200926
1403637212788318976 5.410143852 -1.027250767 4.304031849 -0.040715326 0.365914822 0.082710713 0.926071048
1403637212838319104 5.464945316 -1.051992655 4.353132725 -0.043819282 0.366330117 0.081857115 0.925840974
1403637212888318976 5.523872852 -1.083699465 4.403928280 -0.045041393 0.366973400 0.080131277 0.925678551
1403637212938319104 5.582848549 -1.112266541 4.454168797 -0.046081111 0.367533922 0.077822581 0.925601959
1403637212988318976 5.640799046 -1.141731977 4.502498627 -0.046914313 0.367411613 0.075517073 0.925799608
1403637213038319104 5.699099541 -1.171903253 4.554586411 -0.047245316 0.366771072 0.075334437 0.926051617
1403637213088318976 5.758672714 -1.203133464 4.605170727 -0.046587385 0.365390807 0.076560758 0.926529884
1403637213138319104 5.813817024 -1.232612014 4.659732342 -0.046948142 0.364121497 0.078392833 0.926858127
1403637213188318976 5.870820045 -1.259181023 4.710367203 -0.046361417 0.362461507 0.080300868 0.927374780
1403637213238319104 5.927960396 -1.285159349 4.764764786 -0.045625538 0.361700624 0.080712117 0.927672625
1403637213288318976 5.986052036 -1.308658838 4.817575932 -0.045438405 0.360790074 0.081878878 0.927934110
1403637213338319104 6.042980671 -1.330444813 4.875720024 -0.044038374 0.360814869 0.081119202 0.928058684
1403637213388318976 6.103748798 -1.350442886 4.927730083 -0.042512659 0.360950381 0.080566883 0.928125262
1403637213438319104 6.158384800 -1.374563456 4.983323097 -0.040548246 0.361130983 0.079071656 0.928271472
1403637213488318976 6.218493462 -1.393599749 5.038784504 -0.038829956 0.361534745 0.077660926 0.928306878
1403637213538319104 6.278895378 -1.411283493 5.094243526 -0.037480373 0.361929089 0.075805500 0.928362072
1403637213588318976 6.333089828 -1.430132866 5.147733212 -0.037873805 0.364070058 0.068600059 0.928069293
1403637213638319104 6.392196178 -1.444649220 5.204941273 -0.039233871 0.366016090 0.062622704 0.927669823
1403637213688318976 6.448686600 -1.456640482 5.264569759 -0.042519271 0.367747307 0.056612533 0.927226543
1403637213738319104 6.494573593 -1.471806765 5.319716454 -0.044364449 0.369073212 0.053021304 0.926825523
1403637213788318976 6.554218292 -1.480976343 5.371181965 -0.047816385 0.369060159 0.051016610 0.926771581
1403637213838319104 6.597666740 -1.484652162 5.431217670 -0.048924316 0.369417369 0.049078114 0.926676095
1403637213888318976 6.653231621 -1.496235251 5.495497704 -0.050167002 0.369626045 0.047052547 0.926631451
1403637213938319104 6.691241264 -1.507245064 5.553290844 -0.051749609 0.369882882 0.046959322 0.926446676
1403637213988318976 6.738463402 -1.520457625 5.614512444 -0.049845211 0.369664222 0.044733584 0.926748455
1403637214038319104 6.789430618 -1.527149320 5.683694839 -0.045750249 0.367681473 0.044557583 0.927756369
1403637214088318976 6.846586704 -1.540449858 5.741561890 -0.040000442 0.362944961 0.044236239 0.929900050
1403637214138319104 6.881791115 -1.555093288 5.800910950 -0.034815446 0.357502222 0.048293132 0.932012796
1403637214188318976 6.933238029 -1.570381403 5.869543076 -0.030105550 0.350410938 0.048395723 0.934860289
1403637214238319104 6.968439579 -1.593985319 5.933591366 -0.026868511 0.343966186 0.047862854 0.937376380
1403637214288318976 7.005189896 -1.619504809 5.984632969 -0.023901600 0.336194813 0.044874057 0.940419137
1403637214338319104 7.041440964 -1.636874914 6.049853325 -0.020192651 0.327849180 0.040038805 0.943665206
1403637214388318976 7.072841644 -1.660202980 6.108279228 -0.017164737 0.319012314 0.032365475 0.947042227
1403637214438319104 7.106658459 -1.681931853 6.166045189 -0.016334012 0.309134007 0.022814367 0.950604498
1403637214488318976 7.138464928 -1.704988718 6.215194225 -0.016098052 0.297896236 0.012136076 0.954385400
1403637214538319104 7.156852722 -1.728712678 6.280145168 -0.015504850 0.287948877 0.001272195 0.957519412
1403637214588318976 7.182618141 -1.756496429 6.323616982 -0.015911473 0.278097123 -0.008664805 0.960382104
1403637214638319104 7.200071812 -1.779459596 6.378847599 -0.014536011 0.269680768 -0.020024145 0.962631822
1403637214688318976 7.219515800 -1.799027324 6.438423634 -0.012805049 0.262532145 -0.029875990 0.964375615
1403637214738319104 7.223910809 -1.816713810 6.507086754 -0.011692634 0.257951230 -0.040246636 0.965248525
1403637214788318976 7.233697414 -1.865963578 6.563575745 -0.011410304 0.252648532 -0.047118407 0.966342807
1403637214838319104 7.230469704 -1.882858634 6.620553970 -0.009767701 0.248761848 -0.050005980 0.967223644
1403637214888318976 7.221904755 -1.905324578 6.688102722 -0.009359997 0.245786399 -0.051241234 0.967923403
1403637214938319104 7.224735260 -1.941414595 6.725475788 -0.009277171 0.242200792 -0.052407280 0.968765318
1403637214988318976 7.224388599 -1.971379042 6.768422127 -0.007020469 0.239574984 -0.052252952 0.969445288
1403637215038319104 7.195911407 -2.002206326 6.845577717 -0.006251614 0.239399076 -0.052182090 0.969497800
1403637215088318976 7.203917027 -2.033129215 6.853309155 -0.004283346 0.236407936 -0.052933678 0.970201492
1403637215138319104 7.173450470 -2.036353588 6.917990208 -0.000085800 0.237233967 -0.052563578 0.970029414
1403637215188318976 7.136983871 -2.053991318 6.982469559 0.002586864 0.238250360 -0.051719960 0.969822228
1403637215238319104 7.130100250 -2.070187807 7.038118362 0.005893380 0.235603318 -0.048277423 0.970631599
1403637215288318976 7.105693340 -2.099854231 7.070662975 0.007252976 0.231938973 -0.045538701 0.971636713
1403637215338319104 7.054639816 -2.098847866 7.146955490 0.011913409 0.229068547 -0.041898839 0.972435176
1403637215388318976 7.001914978 -2.097277164 7.202904701 0.018001048 0.224703074 -0.038125772 0.973514736
1403637215438319104 7.007716179 -2.089315414 7.261881828 0.026360171 0.213404417 -0.035467047 0.975964069
1403637215488318976 6.964729309 -2.166891336 7.268875122 0.029075524 0.202559873 -0.032517124 0.978297889
1403637215538319104 6.923467636 -2.167363405 7.297905922 0.035123039 0.191377059 -0.031121178 0.980394125
1403637215588318976 6.973972321 -2.165594578 7.320549965 0.037978340 0.174616501 -0.034508049 0.983298481
1403637215638319104 6.954600811 -2.159326315 7.318192482 0.038761642 0.158730984 -0.035391588 0.985925674
1403637215688318976 6.868841648 -2.110583782 7.347720623 0.039099507 0.147201121 -0.041044954 0.987480819
1403637215738319104 6.792828560 -2.147516012 7.310046196 0.029790517 0.133327693 -0.043325704 0.989676297
1403637215788318976 6.735644341 -2.138608694 7.323674202 0.023783537 0.117822714 -0.043512542 0.991795778
1403637215838319104 6.663390160 -2.162190199 7.334569931 0.013554447 0.104497470 -0.046235055 0.993357360
1403637215888318976 6.603970528 -2.176956654 7.337084770 0.007124577 0.089904360 -0.047611572 0.994786203
1403637215938319104 6.533335209 -2.182554007 7.345984459 0.002697703 0.077824399 -0.046630789 0.995872319
1403637215988318976 6.462720871 -2.197110653 7.347330570 -0.002608701 0.066693038 -0.046621233 0.996680319
1403637216038319104 6.393756866 -2.205941916 7.352396965 -0.003976864 0.054324411 -0.045858949 0.997461796
1403637216088318976 6.325228691 -2.215889215 7.353146076 -0.006141732 0.043098826 -0.044473924 0.998061538
1403637216138319104 6.256171227 -2.236533403 7.345727921 -0.008593812 0.032509759 -0.044437353 0.998446107
1403637216188318976 6.186302662 -2.237624884 7.342392921 -0.007287235 0.022971390 -0.043716505 0.998753250
1403637216238319104 6.121035576 -2.246381044 7.338682175 -0.007738083 0.015253033 -0.042408831 0.998953938
1403637216288318976 6.049922943 -2.255239964 7.333803654 -0.006395527 0.009228894 -0.040798180 0.999104321
1403637216338319104 5.986188889 -2.260090828 7.325561047 -0.004491625 0.004917300 -0.040531479 0.999156058
1403637216388318976 5.921336651 -2.261805058 7.317045212 -0.000771026 0.001475525 -0.040025014 0.999197304
1403637216438319104 5.854936123 -2.261761427 7.310348034 0.004495907 -0.000425014 -0.039605714 0.999205172
1403637216488318976 5.792421818 -2.263491631 7.296131611 0.008390974 -0.001770637 -0.041013807 0.999121785
1403637216538319104 5.733947277 -2.267841339 7.290366650 0.012525694 -0.002849459 -0.040414207 0.999100447
1403637216588318976 5.671787262 -2.260780334 7.277479649 0.015488838 -0.004009240 -0.037484758 0.999169111
1403637216638319104 5.607087612 -2.260138512 7.263273239 0.018030958 -0.004401443 -0.035198718 0.999207973
1403637216688318976 5.545754433 -2.249319077 7.243389606 0.023172243 -0.004667313 -0.031319380 0.999229908
1403637216738319104 5.487416744 -2.249519825 7.227676868 0.027893638 -0.004473920 -0.030001532 0.999150574
1403637216788318976 5.430237770 -2.246743679 7.208052635 0.032524526 -0.003366004 -0.029555712 0.999028206
1403637216838319104 5.371612072 -2.237340450 7.182384491 0.037193820 -0.001423827 -0.030254172 0.998848975
1403637216888318976 5.320461750 -2.227830410 7.149344444 0.041001864 -0.000012416 -0.031794902 0.998653054
1403637216938319104 5.268639565 -2.222466707 7.117866993 0.043093152 0.002329669 -0.033545237 0.998504996
1403637216988318976 5.215829372 -2.215919733 7.079275608 0.041805979 0.004101069 -0.033798974 0.998545468
1403637217038319104 5.166860104 -2.208176613 7.037478924 0.037416682 0.004291321 -0.030771334 0.998816669
1403637217088318976 5.109776497 -2.205139875 6.993292332 0.030918250 0.004011929 -0.023374539 0.999240518
1403637217138319104 5.060534000 -2.190701008 6.943924904 0.026426116 0.003438888 -0.017159585 0.999497592
1403637217188318976 5.017444611 -2.183277369 6.889641762 0.022967700 0.002033089 -0.009123059 0.999692500
1403637217238319104 4.974319935 -2.175285339 6.837961197 0.021114623 0.000958117 -0.001433246 0.999775589
1403637217288318976 4.928783417 -2.160302401 6.787967682 0.019320339 0.001266255 0.003238592 0.999807298
1403637217338319104 4.890678883 -2.143795013 6.732267380 0.017453004 0.001069014 0.007211044 0.999821126
1403637217388318976 4.848157883 -2.127710104 6.679881096 0.016470203 0.001657760 0.011177248 0.999800503
1403637217438319104 4.819110394 -2.106125832 6.619184017 0.015678007 0.002179805 0.014393025 0.999771118
1403637217488318976 4.788104534 -2.082397699 6.560857773 0.015236164 0.002216023 0.016204566 0.999750137
1403637217538319104 4.759618282 -2.061166525 6.498837948 0.016418243 0.001352842 0.014482028 0.999759436
1403637217588318976 4.723562717 -2.035115004 6.439405441 0.018707864 0.000336018 0.010520533 0.999769568
1403637217638319104 4.698071480 -2.009044170 6.380635738 0.021376915 -0.001947017 0.003192767 0.999764502
1403637217688318976 4.680429935 -1.981160522 6.313849926 0.026035689 -0.005657341 -0.009802371 0.999596953
1403637217738319104 4.652583122 -1.952561617 6.243851185 0.029917203 -0.010163927 -0.025250889 0.999181688
1403637217788318976 4.626723289 -1.925174117 6.171131611 0.033333976 -0.016980946 -0.039706588 0.998510838
1403637217838319104 4.607210159 -1.899352908 6.096700191 0.032024629 -0.027649373 -0.050114211 0.997846901
1403637217888318976 4.590870380 -1.872356296 6.017394066 0.031637270 -0.038884804 -0.060679860 0.996897697
1403637217938319104 4.572854519 -1.846037745 5.936933994 0.029300598 -0.049474109 -0.066890918 0.996102095
1403637217988318976 4.549683571 -1.827589512 5.857218742 0.025489511 -0.059422169 -0.071597017 0.995335698
1403637218038319104 4.530093193 -1.798365593 5.767014503 0.023171090 -0.068551771 -0.073905215 0.994636476
1403637218088318976 4.508404732 -1.777049661 5.680838108 0.018137233 -0.076940693 -0.074954346 0.994048774
1403637218138319104 4.484986305 -1.754958034 5.590138435 0.015492377 -0.083187610 -0.076645337 0.993461311
1403637218188318976 4.468108654 -1.725966334 5.495931149 0.013049034 -0.088924877 -0.077826887 0.992907405
1403637218238319104 4.452732563 -1.702509284 5.403904438 0.010570482 -0.093239106 -0.079367407 0.992419064
1403637218288318976 4.430523396 -1.674128056 5.310992718 0.009355389 -0.096577942 -0.080036603 0.992058098
1403637218338319104 4.415873051 -1.643271565 5.212630272 0.009329787 -0.098340526 -0.083173178 0.991627097
1403637218388318976 4.392199516 -1.608512759 5.121198177 0.009636194 -0.099826023 -0.082900696 0.991498590
1403637218438319104 4.372368336 -1.574981332 5.027390480 0.009345735 -0.100784302 -0.082055829 0.991474688
1403637218488318976 4.356765747 -1.538665056 4.928689957 0.010760818 -0.101371236 -0.082704648 0.991346538
1403637218538319104 4.338350773 -1.505646467 4.831747055 0.010305726 -0.101399153 -0.083433241 0.991287529
1403637218588318976 4.319107533 -1.470894814 4.735824585 0.010492953 -0.100440800 -0.083623558 0.991367042
1403637218638319104 4.298531055 -1.443891644 4.636767387 0.007179822 -0.099798895 -0.083828263 0.991444111
1403637218688318976 4.278096676 -1.408025384 4.537147045 0.005303604 -0.098147482 -0.085188262 0.991504908
1403637218738319104 4.264246464 -1.379350066 4.430668354 0.000920525 -0.097847059 -0.083291471 0.991709471
1403637218788318976 4.248795033 -1.347273469 4.324976921 -0.000751473 -0.097162552 -0.082240112 0.991864622
1403637218838319104 4.225718498 -1.315712452 4.221467972 -0.003180915 -0.094135299 -0.086202800 0.991815269
1403637218888318976 4.208833694 -1.277113199 4.108110428 -0.004996492 -0.091547728 -0.090768807 0.991642594
1403637218938319104 4.189128876 -1.234646916 3.999160290 -0.004609325 -0.089410700 -0.094745971 0.991467416
1403637218988318976 4.172073364 -1.186693549 3.892273426 -0.005020737 -0.087194696 -0.099307835 0.991216362
1403637219038319104 4.151667595 -1.137372971 3.785396814 -0.005459131 -0.085409045 -0.102749027 0.991018713
1403637219088318976 4.127227783 -1.088431835 3.681478739 -0.005829486 -0.084113963 -0.104514830 0.990942717
1403637219138319104 4.104495049 -1.036884427 3.570071459 -0.005258149 -0.083701089 -0.105166778 0.990911901
1403637219188318976 4.078326225 -0.982918739 3.464953184 -0.005827521 -0.083169535 -0.104677573 0.991005301
1403637219238319104 4.053069115 -0.937426567 3.351476192 -0.006543297 -0.083039343 -0.103653334 0.991119385
1403637219288318976 4.023214340 -0.887399673 3.247511625 -0.007787996 -0.082897492 -0.102372095 0.991255403
1403637219338319104 3.996033430 -0.843198299 3.137119055 -0.008359465 -0.083137721 -0.099751532 0.991497815
1403637219388318976 3.974628448 -0.800993621 3.022407055 -0.010863567 -0.083292991 -0.098828785 0.991552889
1403637219438319104 3.934226036 -0.758008182 2.910434723 -0.012976552 -0.082804538 -0.097522669 0.991697729
1403637219488318976 3.899993181 -0.717955112 2.793170691 -0.021914838 -0.082663707 -0.095564850 0.991742849
1403637219538319104 3.867512226 -0.673126817 2.680555820 -0.028254477 -0.082259387 -0.094015509 0.991764188
1403637219588318976 3.836215019 -0.636168361 2.566275835 -0.037348989 -0.082278214 -0.092210121 0.991631329
1403637219638319104 3.805169821 -0.600138128 2.443440437 -0.043759666 -0.082128629 -0.090339862 0.991553664
1403637219688318976 3.769331932 -0.570860744 2.335483074 -0.049601488 -0.081740223 -0.089784227 0.991361201
1403637219738319104 3.730499268 -0.527251840 2.230242491 -0.051547159 -0.081042096 -0.088591926 0.991426528
1403637219788318976 3.692010641 -0.501052082 2.116281986 -0.054812111 -0.080632575 -0.087899722 0.991346359
1403637219838319104 3.657073498 -0.470645785 2.002525806 -0.057091951 -0.080401912 -0.088281341 0.991202533
1403637219888318976 3.611799717 -0.445766330 1.896553755 -0.060213156 -0.079946972 -0.087265961 0.991144538
1403637219938319104 3.571336985 -0.419187069 1.796747208 -0.059972331 -0.080406576 -0.086327776 0.991204143
1403637219988318976 3.531377316 -0.401886493 1.687750816 -0.060090519 -0.080228135 -0.086810179 0.991169333
1403637220038319104 3.487134218 -0.381218851 1.588735700 -0.060947381 -0.080234453 -0.086491041 0.991144359
1403637220088318976 3.442175388 -0.361919552 1.493922472 -0.061317671 -0.080222584 -0.085336395 0.991222560
1403637220138319104 3.400352001 -0.355690688 1.387006521 -0.062035933 -0.079465672 -0.087836228 0.991020441
1403637220188318976 3.360606670 -0.346696049 1.288789034 -0.062784418 -0.081008367 -0.085864834 0.991021216
1403637220238319104 3.310874224 -0.333534211 1.197320819 -0.062224317 -0.081151672 -0.083242565 0.991268516
1403637220288318976 3.262312174 -0.327462077 1.105207443 -0.060644053 -0.082198836 -0.078948185 0.991631389
1403637220338319104 3.219077587 -0.319827616 1.011194468 -0.058393613 -0.083789840 -0.073493734 0.992052495
1403637220388318976 3.169285774 -0.321179748 0.920420468 -0.056411643 -0.085165881 -0.067143723 0.992500007
1403637220438319104 3.124199629 -0.320448220 0.830779433 -0.053918667 -0.086158507 -0.062687889 0.992844284
1403637220488318976 3.079825640 -0.316475093 0.743525743 -0.052172840 -0.086922362 -0.058784503 0.993109703
1403637220538319104 3.030011177 -0.318453401 0.662491798 -0.049801830 -0.087233454 -0.055257075 0.993406653
1403637220588318976 2.989830256 -0.314762294 0.577038944 -0.047388170 -0.087894976 -0.052046411 0.993639767
1403637220638319104 2.945979118 -0.312222570 0.496995807 -0.047438085 -0.087129705 -0.052958950 0.993656576
1403637220688318976 2.908728838 -0.305698633 0.415945917 -0.048333373 -0.087230168 -0.052631237 0.993622065
1403637220738319104 2.868515253 -0.294874012 0.340617537 -0.048110560 -0.086417273 -0.053626418 0.993650675
1403637220788318976 2.833473682 -0.286385804 0.262512088 -0.049206674 -0.086212620 -0.054033283 0.993592739
1403637220838319104 2.794625282 -0.277930617 0.188507050 -0.050112762 -0.086060837 -0.054314088 0.993545294
1403637220888318976 2.760144711 -0.269154191 0.112858742 -0.050962158 -0.085494980 -0.055212438 0.993501425
1403637220938319104 2.725473404 -0.257802010 0.044204265 -0.051970426 -0.085272990 -0.055062186 0.993476570
1403637220988318976 2.691923857 -0.246639356 -0.026030034 -0.053130046 -0.083915971 -0.054718200 0.993549824
1403637221038319104 2.659693956 -0.233244956 -0.094875455 -0.056055464 -0.081036478 -0.055173129 0.993602931
1403637221088318976 2.626508951 -0.218223646 -0.154269278 -0.057419989 -0.076813318 -0.054048687 0.993922234
1403637221138319104 2.599729300 -0.203510374 -0.219424933 -0.060223259 -0.071739577 -0.053155959 0.994183600
1403637221188318976 2.571244955 -0.187345088 -0.277821451 -0.061935510 -0.064933136 -0.052293390 0.994591892
1403637221238319104 2.542547226 -0.172010452 -0.336987078 -0.063125722 -0.056877404 -0.051519126 0.995050669
1403637221288318976 2.514835358 -0.153362721 -0.391089439 -0.063537292 -0.048495155 -0.050212681 0.995534956
1403637221338319104 2.489898205 -0.136832178 -0.444336534 -0.063380778 -0.041147910 -0.047549020 0.996006429
1403637221388318976 2.462819338 -0.115086816 -0.498188078 -0.063728049 -0.034862623 -0.045312956 0.996328294
1403637221438319104 2.439899921 -0.097034335 -0.548744082 -0.062214531 -0.029667588 -0.042547897 0.996714056
1403637221488318976 2.411453247 -0.075725928 -0.592130661 -0.062773742 -0.024491021 -0.041305229 0.996871889
1403637221538319104 2.386934757 -0.056437209 -0.639987707 -0.063541837 -0.021036252 -0.037876256 0.997038245
1403637221588318976 2.368122816 -0.036680199 -0.680990994 -0.064236917 -0.017852174 -0.036029365 0.997124255
1403637221638319104 2.342379570 -0.013428152 -0.724836886 -0.064423539 -0.014128438 -0.036092028 0.997169673
1403637221688318976 2.318693161 0.011007771 -0.762061656 -0.065404125 -0.011200116 -0.033618443 0.997229457
1403637221738319104 2.298883200 0.030568764 -0.803548694 -0.065768652 -0.008911533 -0.033083871 0.997246504
1403637221788318976 2.282105207 0.052254438 -0.836255252 -0.066166714 -0.007353545 -0.031534921 0.997283041
1403637221838319104 2.259740353 0.076528184 -0.871054471 -0.066858709 -0.004328407 -0.030100765 0.997298896
1403637221888318976 2.238663912 0.101174414 -0.900983870 -0.067437775 -0.000490773 -0.027344212 0.997348607
1403637221938319104 2.224438667 0.120967135 -0.928600192 -0.068677500 0.004423894 -0.025067901 0.997314095
1403637221988318976 2.207432032 0.150771230 -0.953744888 -0.068295717 0.012275863 -0.022359371 0.997338951
1403637222038319104 2.195638657 0.173065275 -0.980286360 -0.068224475 0.021396965 -0.019190453 0.997255862
1403637222088318976 2.175395966 0.203831464 -0.995068073 -0.068427816 0.032836702 -0.015968489 0.996987641
1403637222138319104 2.166334391 0.227236152 -1.022121668 -0.068460546 0.043969676 -0.011744758 0.996615231
1403637222188318976 2.155324936 0.253555864 -1.031431794 -0.067813635 0.056424767 -0.007513281 0.996072829
1403637222238319104 2.147360086 0.279299498 -1.054584503 -0.064468160 0.067499697 -0.004268628 0.995625138
1403637222288318976 2.138996363 0.306109428 -1.062294841 -0.060798135 0.077494152 -0.002850014 0.995133221
1403637222338319104 2.126410723 0.333128542 -1.079174757 -0.054328866 0.086318336 -0.000683615 0.994784951
1403637222388318976 2.122456312 0.356205434 -1.092477322 -0.047802646 0.093393303 0.001350098 0.994480193
1403637222438319104 2.113304138 0.377139121 -1.104487658 -0.041779760 0.100015268 0.002344657 0.994105577
1403637222488318976 2.106411457 0.402533740 -1.110891819 -0.036135592 0.105541460 0.002676992 0.993754506
1403637222538319104 2.099186182 0.419391990 -1.122292638 -0.033271443 0.109722972 0.003968006 0.993397295
1403637222588318976 2.093878984 0.442905635 -1.135826230 -0.031483196 0.112603121 0.005632286 0.993125141
1403637222638319104 2.087958097 0.459161252 -1.146114826 -0.029560979 0.115578160 0.005217824 0.992844701
1403637222688318976 2.080299377 0.474785179 -1.155205846 -0.030291652 0.117927298 0.004299413 0.992550790
1403637222738319104 2.074132681 0.489527047 -1.162875891 -0.031289432 0.119143866 0.005165747 0.992370427
1403637222788318976 2.071750879 0.498115420 -1.182237864 -0.035039302 0.120007686 0.005971860 0.992136478
1403637222838319104 2.068033218 0.507214367 -1.194544554 -0.039779272 0.119765051 0.005974637 0.991986990
1403637222888318976 2.060064554 0.515198171 -1.200098276 -0.044969663 0.119889833 0.006580613 0.991746366
1403637222938319104 2.057592630 0.522585690 -1.219884038 -0.050958991 0.118950568 0.007952032 0.991559744
1403637222988318976 2.053088665 0.523749053 -1.230436563 -0.056007300 0.118553422 0.007385285 0.991339386
1403637223038319104 2.048744678 0.521676123 -1.241016388 -0.059850622 0.117667630 0.007174904 0.991221845
1403637223088318976 2.044129133 0.522513270 -1.252159357 -0.062127192 0.116851278 0.007343029 0.991177142
1403637223138319104 2.043611765 0.516527057 -1.257705927 -0.063116968 0.116094559 0.006503115 0.991209388
1403637223188318976 2.041431904 0.508389831 -1.270491362 -0.062704548 0.115049824 0.006328257 0.991358459
1403637223238319104 2.037576914 0.498169988 -1.271983385 -0.060786281 0.114615582 0.004714787 0.991537213
1403637223288318976 2.040616035 0.483569115 -1.281682253 -0.056797784 0.113245420 0.002713766 0.991938591
1403637223338319104 2.038484335 0.468978137 -1.284416676 -0.051818702 0.112110965 0.000974067 0.992343187
1403637223388318976 2.035412788 0.451231837 -1.287010431 -0.048157405 0.111225016 -0.001785495 0.992626131
1403637223438319104 2.040833235 0.430477232 -1.302169800 -0.043977935 0.109514616 -0.002796718 0.993007898
1403637223488318976 2.038280964 0.409773529 -1.298857212 -0.041345272 0.108816139 -0.004277797 0.993192494
1403637223538319104 2.036720991 0.390796006 -1.302543759 -0.038280282 0.108111218 -0.005639705 0.993385494
1403637223588318976 2.037708282 0.368094265 -1.302660942 -0.036182553 0.107493982 -0.006412540 0.993526459
1403637223638319104 2.039483309 0.349668294 -1.304884195 -0.034357950 0.107157692 -0.007311429 0.993621290
1403637223688318976 2.039253950 0.331626892 -1.308441520 -0.033376981 0.106788129 -0.007941880 0.993689716
1403637223738319104 2.040837049 0.316007346 -1.310302734 -0.032983229 0.106746316 -0.008828359 0.993699849
1403637223788318976 2.040132284 0.306016475 -1.307081699 -0.031575847 0.106610581 -0.008942404 0.993759155
1403637223838319104 2.041669607 0.290832251 -1.307157755 -0.031304039 0.106337897 -0.009790608 0.993788958
1403637223888318976 2.041283607 0.280880958 -1.304073215 -0.030380137 0.106588863 -0.010201083 0.993786573
1403637223938319104 2.042212009 0.271846056 -1.305606842 -0.029971085 0.106907807 -0.011322399 0.993752599
1403637223988318976 2.044300079 0.263851702 -1.299692392 -0.029640717 0.106793843 -0.010848879 0.993780077
1403637224038319104 2.041378975 0.259973973 -1.298668385 -0.029044762 0.107108451 -0.011090981 0.993761122
1403637224088318976 2.043433905 0.254795760 -1.296441078 -0.029589446 0.106917381 -0.011298332 0.993763268
1403637224138319104 2.047276735 0.252169341 -1.295302153 -0.028879797 0.107287936 -0.011748937 0.993739009
1403637224188318976 2.044387102 0.254028529 -1.289089441 -0.028428195 0.107616313 -0.011947182 0.993714154
1403637224238319104 2.045199633 0.255551040 -1.286793947 -0.027974315 0.108094513 -0.012885428 0.993663371
1403637224288318976 2.049021006 0.257464796 -1.281307697 -0.027097601 0.108098678 -0.013093067 0.993684530
1403637224338319104 2.047752142 0.261491627 -1.278972864 -0.026550146 0.107964925 -0.013236766 0.993711948
1403637224388318976 2.047539473 0.268066466 -1.267840624 -0.026610158 0.108411498 -0.014242974 0.993647814
1403637224438319104 2.047078133 0.274888337 -1.265448809 -0.026564119 0.108886600 -0.015342213 0.993580699
1403637224488318976 2.046872616 0.282336354 -1.260426283 -0.026315190 0.109072082 -0.015640583 0.993562341
1403637224538319104 2.046713829 0.290600985 -1.258547425 -0.025783276 0.109181963 -0.016427560 0.993551552
1403637224588318976 2.045450211 0.302122951 -1.248746157 -0.025130305 0.109074928 -0.015196297 0.993599594
1403637224638319104 2.047708988 0.307675272 -1.250180006 -0.024795821 0.107776031 -0.012955429 0.993781507
1403637224688318976 2.045677185 0.315335393 -1.242977619 -0.023742909 0.106108479 -0.008374456 0.994035780
1403637224738319104 2.038142920 0.321480364 -1.236416936 -0.024767809 0.105165884 -0.004293000 0.994136930
1403637224788318976 2.035248518 0.325001568 -1.231355190 -0.025417790 0.104901657 -0.002980231 0.994153261
1403637224838319104 2.036796570 0.328032017 -1.231580257 -0.025859164 0.104885995 -0.002691319 0.994144320
1403637224888318976 2.029272079 0.331163079 -1.227322936 -0.024752676 0.106097907 -0.005481937 0.994032443
1403637224938319104 2.027886391 0.336142182 -1.223199129 -0.024184108 0.107345402 -0.008958036 0.993887246
1403637224988318976 2.025627136 0.340933204 -1.221540451 -0.024094362 0.108049832 -0.011483961 0.993787110
1403637225038319104 2.026670694 0.344622910 -1.228874445 -0.024283620 0.108111143 -0.012933736 0.993758023
1403637225088318976 2.022634745 0.357134938 -1.219441652 -0.023909604 0.108950324 -0.014425733 0.993654907
1403637225138319104 2.015171766 0.362770110 -1.220637679 -0.023167854 0.109374903 -0.015989609 0.993601918
1403637225188318976 2.017050505 0.377042890 -1.220557928 -0.022086233 0.109008141 -0.015677949 0.993671775
1403637225238319104 2.011251211 0.385019362 -1.219899178 -0.021946054 0.108899347 -0.016901650 0.993666768
1403637225288318976 2.012214184 0.400632441 -1.218154192 -0.021531343 0.107696705 -0.015870709 0.993823886
1403637225338319104 2.011237383 0.410930097 -1.220769882 -0.020720055 0.107267842 -0.016576516 0.993875980
1403637225388318976 2.000323057 0.423160136 -1.213065863 -0.019864190 0.107623197 -0.017432509 0.993840396
1403637225438319104 1.995738745 0.433190525 -1.216014504 -0.018426381 0.106953584 -0.017639423 0.993936718
1403637225488318976 1.991196752 0.441907316 -1.214663863 -0.017737206 0.106662802 -0.017878931 0.993976235
1403637225538319104 1.984436393 0.447590947 -1.217948675 -0.018012935 0.106290668 -0.018803274 0.993994057
1403637225588318976 1.973561883 0.453871161 -1.219123006 -0.019310040 0.106101409 -0.018725701 0.993991435
1403637225638319104 1.967678666 0.454718590 -1.228456974 -0.021614971 0.105650589 -0.019661514 0.993973911
1403637225688318976 1.958632827 0.456288397 -1.232708454 -0.025316199 0.105304003 -0.018496316 0.993945718
1403637225738319104 1.949715376 0.454929292 -1.242391586 -0.027445383 0.105202734 -0.019167423 0.993887186
1403637225788318976 1.940095544 0.452003300 -1.250145197 -0.031462640 0.105115868 -0.019126385 0.993778110
1403637225838319104 1.926138520 0.447875559 -1.252414942 -0.034843832 0.105147131 -0.018224323 0.993678927
1403637225888318976 1.916471243 0.439316720 -1.263758659 -0.037449185 0.104617253 -0.018064182 0.993643045
1403637225938319104 1.903490901 0.430401713 -1.274116397 -0.035021104 0.104251683 -0.018035475 0.993770480
1403637225988318976 1.888391137 0.420704663 -1.275944233 -0.031117538 0.104334362 -0.018588576 0.993881524
1403637226038319104 1.876659393 0.404496431 -1.291871548 -0.026739907 0.103733614 -0.018654013 0.994070590
1403637226088318976 1.863906145 0.393151730 -1.299657941 -0.023844676 0.103599027 -0.018960899 0.994152486
1403637226138319104 1.849122405 0.381418347 -1.305637360 -0.020780509 0.103600144 -0.019118950 0.994218111
1403637226188318976 1.836938143 0.372813463 -1.314263582 -0.019231455 0.103551775 -0.018951446 0.994257510
1403637226238319104 1.819815397 0.364694357 -1.322120786 -0.017979719 0.103629574 -0.019385621 0.994264483
1403637226288318976 1.805375576 0.357733548 -1.328515172 -0.019241700 0.104008220 -0.020193964 0.994185209
1403637226338319104 1.792018890 0.353201628 -1.340763927 -0.023127507 0.103947148 -0.020081175 0.994111121
1403637226388318976 1.776929975 0.350986749 -1.345367193 -0.028173873 0.104211859 -0.020753961 0.993939340
1403637226438319104 1.761037350 0.349334478 -1.351698160 -0.035240661 0.104644492 -0.020579079 0.993672013
1403637226488318976 1.742249608 0.351123065 -1.357603669 -0.040825699 0.104756109 -0.019916836 0.993460000
1403637226538319104 1.729330540 0.347317815 -1.369458437 -0.044969872 0.104644604 -0.020350283 0.993283987
1403637226588318976 1.711906910 0.349393964 -1.378322959 -0.048429161 0.104793444 -0.020922327 0.993093789
1403637226638319104 1.696028471 0.348783821 -1.382861137 -0.050247341 0.104897343 -0.021119056 0.992988288
1403637226688318976 1.679108143 0.350459546 -1.384792805 -0.051241875 0.104848661 -0.020414399 0.992957354
1403637226738319104 1.663218260 0.352317929 -1.391839266 -0.052047480 0.104072638 -0.019018317 0.993024766
1403637226788318976 1.643370152 0.355213642 -1.388139963 -0.052695114 0.103859395 -0.018769411 0.993017673
1403637226838319104 1.620980740 0.361352146 -1.389086366 -0.052130509 0.104023151 -0.018671971 0.993032217
1403637226888318976 1.604435802 0.364747256 -1.384848714 -0.051541071 0.103444651 -0.016280439 0.993165493
1403637226938319104 1.584540486 0.369550526 -1.383808374 -0.050271563 0.102855623 -0.012285922 0.993349195
1403637226988318976 1.567760944 0.374879986 -1.382182240 -0.048296288 0.101250947 -0.006988266 0.993663371
1403637227038319104 1.548356652 0.379539490 -1.379247665 -0.045693260 0.099154077 0.000446388 0.994022310
1403637227088318976 1.530427217 0.383344591 -1.373358488 -0.042770106 0.097362995 0.008274581 0.994295061
1403637227138319104 1.516171813 0.385872304 -1.370176792 -0.039670989 0.095495306 0.015303688 0.994521320
1403637227188318976 1.501217127 0.385668814 -1.367655993 -0.038855568 0.095444113 0.017134631 0.994528532
1403637227238319104 1.486947060 0.385950923 -1.361416340 -0.037543938 0.095836408 0.018281505 0.994520783
1403637227288318976 1.475304365 0.384901136 -1.354384184 -0.037048336 0.097970970 0.014064148 0.994399965
1403637227338319104 1.465100884 0.378363788 -1.353253722 -0.037990626 0.099770419 0.009815686 0.994236469
1403637227388318976 1.455756307 0.373439997 -1.347760677 -0.038027547 0.101671815 0.005599993 0.994075179
1403637227438319104 1.449946046 0.368538499 -1.344977021 -0.039716303 0.103141852 0.002165626 0.993871033
1403637227488318976 1.439266682 0.363608867 -1.336003065 -0.040666569 0.104629897 0.000313239 0.993679345
1403637227538319104 1.433825016 0.358750284 -1.335951209 -0.041293118 0.105205722 -0.000126207 0.993592799
1403637227588318976 1.426882029 0.357567132 -1.328819394 -0.042052936 0.105524257 0.001064974 0.993526578
1403637227638319104 1.419688582 0.356881499 -1.323331833 -0.041716393 0.105091542 0.004833277 0.993575454
1403637227688318976 1.412328959 0.360668927 -1.309981346 -0.042228960 0.105019003 0.008033914 0.993540704
1403637227738319104 1.406929493 0.360881120 -1.301280975 -0.042406563 0.104623288 0.010368730 0.993553281
1403637227788318976 1.404141903 0.362950951 -1.294519544 -0.042357322 0.103793621 0.012803199 0.993614018
1403637227838319104 1.400736094 0.365362197 -1.287919521 -0.042086240 0.105135784 0.010568251 0.993510723
1403637227888318976 1.399922848 0.367402971 -1.278651714 -0.037896518 0.105667308 0.008348108 0.993644059
1403637227938319104 1.399388194 0.371129185 -1.267782331 -0.032631747 0.106933571 0.003882372 0.993722975
1403637227988318976 1.397761703 0.376437634 -1.254422545 -0.028111156 0.108422384 -0.000285747 0.993707359
1403637228038319104 1.398144960 0.381829649 -1.247277141 -0.023080587 0.109642215 -0.005312707 0.993688941
1403637228088318976 1.398648977 0.387920797 -1.237899780 -0.020647470 0.109474935 -0.007568871 0.993746281
1403637228138319104 1.398724675 0.394649565 -1.229108572 -0.017382782 0.108889394 -0.007972174 0.993869901
1403637228188318976 1.398138404 0.400546223 -1.217336893 -0.016188238 0.108305767 -0.009745813 0.993938029
1403637228238319104 1.398204088 0.407119155 -1.210710168 -0.013654391 0.107217982 -0.009231782 0.994098902
1403637228288318976 1.398208857 0.410989344 -1.209429741 -0.012916837 0.106809355 -0.010302889 0.994142234
1403637228338319104 1.394721031 0.410595238 -1.203602672 -0.012257071 0.106601626 -0.010540911 0.994170368
1403637228388318976 1.391909719 0.413851023 -1.196147919 -0.012733981 0.106848828 -0.013128053 0.994107068
1403637228438319104 1.391561151 0.412911296 -1.198274493 -0.011897835 0.106182404 -0.014171655 0.994174480
1403637228488318976 1.388898253 0.410627007 -1.198862553 -0.011308670 0.106556855 -0.016330460 0.994108140
1403637228538319104 1.384381413 0.407290578 -1.198893309 -0.010300994 0.106985345 -0.018427152 0.994036436
1403637228588318976 1.379918694 0.403493047 -1.200537801 -0.009841147 0.107214838 -0.020724427 0.993971109
1403637228638319104 1.374571681 0.395926058 -1.208108306 -0.010407727 0.107423432 -0.022084409 0.993913531
1403637228688318976 1.368204117 0.390998662 -1.213509560 -0.013398047 0.107482418 -0.021321394 0.993888021
1403637228738319104 1.359541416 0.387048811 -1.215305448 -0.017848561 0.107188076 -0.018928625 0.993898332
1403637228788318976 1.352042913 0.381249666 -1.223661423 -0.022462416 0.105952591 -0.015275593 0.994000077
1403637228838319104 1.344667673 0.377599508 -1.229410768 -0.027115587 0.104880422 -0.012182592 0.994040489
1403637228888318976 1.335752964 0.376205713 -1.235887766 -0.029996248 0.104668520 -0.008217683 0.994020700
1403637228938319104 1.327632785 0.376046300 -1.242043972 -0.030462515 0.105132826 -0.008034324 0.993959069
1403637228988318976 1.320477486 0.376485914 -1.246324539 -0.029920438 0.106519319 -0.010810804 0.993801534
1403637229038319104 1.312594056 0.377154350 -1.250772953 -0.028622683 0.107326426 -0.014117785 0.993711472
1403637229088318976 1.305045247 0.379573643 -1.256682754 -0.025298163 0.107846476 -0.015829084 0.993719578
1403637229138319104 1.294627070 0.380678117 -1.266160965 -0.022378732 0.108532429 -0.018178353 0.993674755
1403637229188318976 1.287664294 0.386119783 -1.264500380 -0.020661645 0.109224759 -0.020633694 0.993588090
1403637229238319104 1.279681444 0.391078949 -1.272889972 -0.019787369 0.109877743 -0.021916738 0.993506432
1403637229288318976 1.268745422 0.398373127 -1.276730895 -0.019637324 0.111414798 -0.022563186 0.993323743
1403637229338319104 1.258878469 0.406573057 -1.277434587 -0.020614475 0.114752024 -0.021797800 0.992941022
1403637229388318976 1.247375488 0.416394740 -1.284290195 -0.023947183 0.118547022 -0.016350195 0.992524981
1403637229438319104 1.238278389 0.427077502 -1.290721178 -0.029484754 0.123386040 -0.007599103 0.991891563
1403637229488318976 1.228455901 0.436399579 -1.296160221 -0.035354968 0.129461557 0.003568453 0.990947485
1403637229538319104 1.217304230 0.447886676 -1.301419020 -0.040232178 0.136793882 0.016814476 0.989639401
1403637229588318976 1.208567619 0.459012717 -1.304672003 -0.044864278 0.145905048 0.029346416 0.987844944
1403637229638319104 1.199047685 0.471281826 -1.302134037 -0.048098482 0.157200634 0.041685298 0.985513449
1403637229688318976 1.192479491 0.482821524 -1.314760685 -0.050087821 0.169512883 0.053133197 0.982819140
1403637229738319104 1.192336917 0.495468289 -1.313322306 -0.051072247 0.183684722 0.059179321 0.979872108
1403637229788318976 1.189881563 0.508360982 -1.318562746 -0.049410872 0.201326683 0.058026936 0.976554692
1403637229838319104 1.197957158 0.520450532 -1.315927029 -0.045268252 0.218933746 0.054485522 0.973164976
1403637229888318976 1.202126026 0.531622171 -1.317899823 -0.040726162 0.237349600 0.049635172 0.969300210
1403637229938319104 1.205586910 0.544928193 -1.317837000 -0.036613971 0.255477041 0.047272053 0.964964390
1403637229988318976 1.213463902 0.558434963 -1.321577072 -0.031619985 0.271862268 0.046203393 0.960706174
1403637230038319104 1.217092395 0.572041392 -1.316179991 -0.031001046 0.288230687 0.047599491 0.955874622
1403637230088318976 1.223232031 0.582069457 -1.318527222 -0.032195933 0.301259041 0.053399660 0.951501369
1403637230138319104 1.226179361 0.592297614 -1.313468695 -0.035310432 0.314245462 0.061735369 0.946674049
1403637230188318976 1.230473995 0.601219058 -1.314136505 -0.037904877 0.325725138 0.068416059 0.942223787
1403637230238319104 1.235404611 0.608012974 -1.311755657 -0.039794445 0.335682631 0.072502747 0.938337326
1403637230288318976 1.237259507 0.609436572 -1.310797215 -0.042066600 0.344610482 0.074278429 0.934856534
1403637230338319104 1.239570141 0.611938596 -1.307716846 -0.042026866 0.351797193 0.074673221 0.932146132
1403637230388318976 1.242445707 0.609122694 -1.307782292 -0.039483782 0.357153475 0.075915858 0.930117846
1403637230438319104 1.247672558 0.605510712 -1.309620261 -0.034410663 0.361757576 0.074099623 0.928685427
1403637230488318976 1.248931170 0.603019536 -1.309789777 -0.027866088 0.365398973 0.071939945 0.927648485
1403637230538319104 1.251410246 0.594831705 -1.303845882 -0.021887830 0.369351864 0.069910534 0.926397681
1403637230588318976 1.257536173 0.583801150 -1.296913862 -0.014899210 0.374110997 0.067274205 0.924820602
1403637230638319104 1.258910418 0.576427937 -1.291212440 -0.008455031 0.379617065 0.068804279 0.922542870
1403637230688318976 1.262097597 0.562121809 -1.305786014 -0.005082311 0.384974688 0.072281837 0.920078278
1403637230738319104 1.258623719 0.551064610 -1.308492541 -0.004636776 0.391841352 0.078682207 0.916650414
1403637230788318976 1.255789995 0.541867197 -1.301334023 -0.007043810 0.399811864 0.085850783 0.912540674
1403637230838319104 1.260135889 0.527880549 -1.311125278 -0.012568100 0.407127172 0.097334653 0.908083439
1403637230888318976 1.257606983 0.518750370 -1.317920566 -0.017906461 0.417160094 0.107985698 0.902217209
1403637230938319104 1.258502722 0.510470569 -1.311512232 -0.022905050 0.428498626 0.117393948 0.895590842
1403637230988318976 1.254438281 0.502690434 -1.323013067 -0.026922675 0.440820962 0.126304045 0.888256371
1403637231038319104 1.260797739 0.498436689 -1.314281702 -0.029979784 0.455001086 0.133238152 0.879956186
1403637231088318976 1.252610207 0.486425638 -1.315245867 -0.031005116 0.470086247 0.140245527 0.870855212
1403637231138319104 1.254142880 0.485516816 -1.320642471 -0.031778600 0.485947281 0.146560073 0.861025870
1403637231188318976 1.200391293 0.459972382 -1.328958035 -0.030649167 0.503731310 0.152557239 0.849730313
1403637231238319104 1.178283691 0.448656708 -1.337741733 -0.029397292 0.521229208 0.159549817 0.837854266
1403637231288318976 1.175202370 0.451814711 -1.339445949 -0.026792064 0.538691163 0.167059764 0.825339317
1403637231338319104 1.175765753 0.480564237 -1.324577451 -0.022670222 0.557014823 0.170998216 0.812391579
1403637231388318976 1.194124699 0.461879671 -1.340312719 -0.019744638 0.574415624 0.179090470 0.798488259
1403637231438319104 1.178462505 0.479973316 -1.342275500 -0.015060693 0.592491150 0.184283584 0.784070730
1403637231488318976 1.193757772 0.498574793 -1.332922339 -0.011126278 0.610178053 0.193488166 0.768193483
1403637231538319104 1.215843081 0.534370661 -1.355350018 -0.007798900 0.625621796 0.203867033 0.752977312
1403637231588318976 1.210560799 0.546723723 -1.334204197 -0.006714966 0.643751323 0.212332457 0.735155821
1403637231638319104 1.237276673 0.594208121 -1.303444505 -0.003524031 0.662382185 0.220026821 0.716118455
1403637231688318976 1.234665632 0.586732507 -1.349762321 -0.006930039 0.677251577 0.226102844 0.700114131
1403637231738319104 1.171060443 0.619725347 -1.401692629 -0.002528048 0.691920578 0.231938943 0.683698595
1403637231788318976 1.128642321 0.615508080 -1.418136477 -0.001954071 0.706581712 0.236343056 0.666993499
1403637231838319104 1.088501453 0.602645040 -1.464024425 -0.002514140 0.717425406 0.242134288 0.653196335
1403637231888318976 1.012711167 0.576965332 -1.328019023 -0.005027539 0.733605802 0.245883182 0.633513033
1403637231938319104 1.040737391 0.592373610 -1.258598804 -0.003901850 0.746519208 0.250146419 0.616539180
1403637231988318976 1.066861153 0.613711298 -1.284473896 -0.002874955 0.755704463 0.253723741 0.603760481
1403637232038319104 1.087252855 0.623404384 -1.293249011 0.004603974 0.766135275 0.253882498 0.590389073
1403637232088318976 1.114785314 0.651018381 -1.313512802 0.014358031 0.776770294 0.251705527 0.577118814
1403637232138319104 1.140073180 0.663294613 -1.340586782 0.021703769 0.786519170 0.249510318 0.564500809
1403637232188318976 1.169665337 0.686864078 -1.375416279 0.029386261 0.795254588 0.248570502 0.552195013
1403637232238319104 1.191277742 0.701725662 -1.409379125 0.032083463 0.803282917 0.248372793 0.540387034
1403637232288318976 1.223384142 0.719257593 -1.452665806 0.033014763 0.811221838 0.247889102 0.528564215
1403637232338319104 1.235743284 0.740817070 -1.481013417 0.033657618 0.819570601 0.245286360 0.516725957
1403637232388318976 1.255148649 0.751900196 -1.529267550 0.032428421 0.827823162 0.242305592 0.504920959
1403637232438319104 1.276490927 0.764212012 -1.551122427 0.032507926 0.835815847 0.241264820 0.492083699
1403637232488318976 1.294816732 0.775375605 -1.588338017 0.034905389 0.842695415 0.242901281 0.479212880
1403637232538319104 1.313360095 0.781070590 -1.629281640 0.038614266 0.846828282 0.251963258 0.466803342
1403637232588318976 1.331864357 0.789554477 -1.664102674 0.040782947 0.850928545 0.261209041 0.453902215
1403637232638319104 1.343223333 0.782866001 -1.707446456 0.043876547 0.854358673 0.272601128 0.440266609
1403637232688318976 1.349549413 0.814042211 -1.754943848 0.047416873 0.858212471 0.280214548 0.427437425
1403637232738319104 1.361392140 0.817838967 -1.793020725 0.048622236 0.861712098 0.289635539 0.413762480
1403637232788318976 1.378307581 0.813178599 -1.851865411 0.050203152 0.864378095 0.299557060 0.400743932
1403637232838319104 1.374797821 0.825739384 -1.908333540 0.048282284 0.866671026 0.306870967 0.390359342
1403637232888318976 1.390498757 0.823417425 -1.956095934 0.042808395 0.869258285 0.313017070 0.380233973
1403637232938319104 1.393142700 0.822744191 -2.016463995 0.037961531 0.870472670 0.319740802 0.372293055
1403637232988318976 1.400540590 0.838674128 -2.086860180 0.032662813 0.872205257 0.322465211 0.366343170
1403637233038319104 1.409696102 0.832295716 -2.150131702 0.025790252 0.873345971 0.325962543 0.361040264
1403637233088318976 1.413030386 0.833517492 -2.221732378 0.019888025 0.873981297 0.328551441 0.357512385
1403637233138319104 1.424877286 0.834862232 -2.292430878 0.014023771 0.874288201 0.331313550 0.354478240
1403637233188318976 1.430568576 0.842953920 -2.368031025 0.008484280 0.873453856 0.334945738 0.353295594
1403637233238319104 1.435523510 0.849504948 -2.447237015 0.004951150 0.872498810 0.337945729 0.352865398
1403637233288318976 1.453334332 0.852428079 -2.525270462 0.000052636 0.871453464 0.341492236 0.352068156
1403637233338319104 1.464630246 0.872048020 -2.606043577 -0.003062867 0.870104194 0.344059169 0.352891833
1403637233388318976 1.474628448 0.877120614 -2.695412636 -0.006222704 0.867953062 0.348435223 0.353852600
1403637233438319104 1.491649508 0.901267409 -2.784347057 -0.010634712 0.866761744 0.349945903 0.355174333
1403637233488318976 1.514131784 0.924734354 -2.871522903 -0.018896768 0.867449939 0.346710026 0.356322527
1403637233538319104 1.526779652 0.951769173 -2.963564396 -0.030624442 0.869999945 0.336921871 0.358672529
1403637233588318976 1.553440213 0.980218410 -3.055504799 -0.045651384 0.874867737 0.320188880 0.360557199
1403637233638319104 1.582569718 1.012835503 -3.152723312 -0.060121030 0.880386889 0.300036073 0.362329572
1403637233688318976 1.611333489 1.062617779 -3.238859177 -0.072823383 0.885911107 0.278315902 0.363866031
1403637233738319104 1.644882917 1.090140939 -3.339832783 -0.083763659 0.889795482 0.260993123 0.364870071
1403637233788318976 1.686745048 1.141793251 -3.426009655 -0.092568427 0.893779457 0.243519485 0.365085781
1403637233838319104 1.730446577 1.174453259 -3.509223938 -0.099054180 0.896130741 0.231895879 0.365188032
1403637233888318976 1.782601237 1.197943211 -3.595693350 -0.105301715 0.897545993 0.223444119 0.365233451
1403637233938319104 1.829528570 1.239951849 -3.676985979 -0.109217025 0.898548245 0.217290759 0.365331978
1403637233988318976 1.880308628 1.282356501 -3.750528336 -0.113028787 0.899115503 0.213151708 0.365215272
1403637234038319104 1.938843131 1.306421161 -3.817055225 -0.118247658 0.899937272 0.207647339 0.364709437
1403637234088318976 2.004093409 1.348142147 -3.881360054 -0.122183330 0.901112676 0.200521067 0.364497572
1403637234138319104 2.066819191 1.387757540 -3.938090324 -0.126800552 0.902412891 0.193213269 0.363649905
1403637234188318976 2.141376495 1.416173339 -3.988507748 -0.131456062 0.903542757 0.186712623 0.362585366
1403637234238319104 2.212639809 1.463578105 -4.037122250 -0.130558789 0.904642284 0.182554156 0.362285376
1403637234288318976 2.295318842 1.483687758 -4.076713562 -0.127347067 0.905751765 0.180713996 0.361578405
1403637234338319104 2.388210297 1.504774809 -4.103484631 -0.121887833 0.906719506 0.180199742 0.361290902
1403637234388318976 2.471928835 1.535424232 -4.133066654 -0.112053595 0.907102644 0.181363910 0.362926871
1403637234438319104 2.569903612 1.565870404 -4.152840614 -0.100078873 0.906980217 0.183142081 0.365827978
1403637234488318976 2.671291590 1.587226391 -4.163737774 -0.090550549 0.906173646 0.183818132 0.369946986
1403637234538319104 2.764361620 1.618065119 -4.174936771 -0.078278318 0.904868960 0.183102772 0.376242042
1403637234588318976 2.861370325 1.632599354 -4.177423477 -0.067018352 0.902560830 0.184898317 0.383020908
1403637234638319104 2.963922262 1.673077941 -4.186103344 -0.055768583 0.899909198 0.184255615 0.391284049
1403637234688318976 3.067394972 1.686300635 -4.164443970 -0.048344873 0.897351563 0.183722913 0.398332536
1403637234738319104 3.163952112 1.705615163 -4.167371273 -0.039647710 0.892779171 0.185538039 0.408593982
1403637234788318976 3.272750378 1.726995230 -4.143426418 -0.030292446 0.888607144 0.187256560 0.417605937
1403637234838319104 3.352921963 1.750288606 -4.126374245 -0.020804584 0.883479357 0.188687131 0.428285629
1403637234888318976 3.464879513 1.790148139 -4.113230705 -0.010080417 0.877347946 0.191572830 0.439839572
1403637234938319104 3.569957018 1.812180281 -4.085152149 -0.001852968 0.871807277 0.192929715 0.450251877
1403637234988318976 3.659664154 1.818005800 -4.056163788 0.002210355 0.866123974 0.194088146 0.460601985
1403637235038319104 3.762935162 1.824483156 -4.018429756 0.002166133 0.861596704 0.192975804 0.469474941
1403637235088318976 3.848637342 1.842720151 -3.988802433 0.002002430 0.856269836 0.190073848 0.480281055
1403637235138319104 3.937480211 1.850802183 -3.961756945 0.000412847 0.850493968 0.188452616 0.491065681
1403637235188318976 4.023592949 1.856001258 -3.929940224 -0.000646486 0.844853759 0.185962364 0.501637101
1403637235238319104 4.108613491 1.871076703 -3.894966602 -0.001439488 0.839602828 0.183211610 0.511369288
1403637235288318976 4.190552235 1.861891031 -3.854251146 -0.005408401 0.834921539 0.184619337 0.518451989
1403637235338319104 4.266713142 1.867088318 -3.813464403 -0.010178382 0.830490589 0.185982555 0.524968803
1403637235388318976 4.348718166 1.871175170 -3.778573751 -0.014948791 0.825151563 0.193654433 0.530470908
1403637235438319104 4.425908089 1.888047457 -3.721637726 -0.018761661 0.820910037 0.198652849 0.535062432
1403637235488318976 4.500589848 1.876798034 -3.702828407 -0.023795055 0.814007044 0.207885027 0.541858077
1403637235538319104 4.571373940 1.882881761 -3.663808346 -0.026234215 0.808378041 0.213032499 0.548136592
1403637235588318976 4.660883904 1.874034286 -3.610766411 -0.031329650 0.804885864 0.215053722 0.552203774
1403637235638319104 4.732714653 1.868181586 -3.578578472 -0.032447606 0.800000250 0.215839073 0.558891952
1403637235688318976 4.805539131 1.853401661 -3.524033546 -0.033106014 0.796808481 0.212960690 0.564489126
1403637235738319104 4.883101463 1.854347229 -3.478518963 -0.032092176 0.794346154 0.204749331 0.571018398
1403637235788318976 4.959698200 1.821625471 -3.446615219 -0.035284545 0.791281581 0.195218086 0.578375638
1403637235838319104 5.029305458 1.793142080 -3.405267000 -0.037626561 0.789423108 0.181443796 0.585212350
1403637235888318976 5.104675770 1.772228360 -3.364795685 -0.041163385 0.786480844 0.168864414 0.592653573
1403637235938319104 5.177576065 1.756137252 -3.316490412 -0.047193639 0.783754289 0.155007690 0.599561930
1403637235988318976 5.243008137 1.731352806 -3.268937588 -0.051162850 0.778648496 0.148325846 0.607526422
1403637236038319104 5.317126751 1.701493025 -3.225039959 -0.056269798 0.773103237 0.140976593 0.615849555
1403637236088318976 5.389293671 1.678501487 -3.169318199 -0.059173662 0.767323673 0.135954767 0.623882353
1403637236138319104 5.461852074 1.648329139 -3.100655079 -0.062927313 0.761741400 0.129962206 0.631585300
1403637236188318976 5.523869991 1.619058847 -3.039241791 -0.065425374 0.755060673 0.126617759 0.639977217
1403637236238319104 5.590652943 1.572638512 -2.971508503 -0.067881741 0.748803139 0.122201525 0.647883236
1403637236288318976 5.652155876 1.533789873 -2.899240255 -0.067333795 0.741780221 0.120405436 0.656300843
1403637236338319104 5.718414307 1.489852428 -2.824400425 -0.066026181 0.734348655 0.118332647 0.665109038
1403637236388318976 5.791035175 1.454074383 -2.745231867 -0.064953215 0.726579189 0.115865737 0.674120843
1403637236438319104 5.845335484 1.397419691 -2.669240713 -0.061900374 0.718558311 0.117267735 0.682708263
1403637236488318976 5.904406548 1.343647957 -2.584744215 -0.056961130 0.711266160 0.118254013 0.690559089
1403637236538319104 5.968755245 1.298990846 -2.481161356 -0.053455722 0.706925094 0.117268637 0.695447683
1403637236588318976 6.021600246 1.238275290 -2.397700548 -0.049498249 0.701708615 0.118175007 0.700849235
1403637236638319104 6.077181339 1.194829702 -2.307998180 -0.044680778 0.698642552 0.114742845 0.704795182
1403637236688318976 6.128583908 1.136674285 -2.205453396 -0.041725632 0.696135402 0.113365293 0.707674205
1403637236738319104 6.182705879 1.101210117 -2.119608879 -0.035425633 0.692561448 0.107668124 0.712398171
1403637236788318976 6.231134415 1.056511164 -2.027672529 -0.029444648 0.688198984 0.103170499 0.717545152
1403637236838319104 6.280931950 1.005086422 -1.920411110 -0.022278998 0.683542669 0.099322781 0.722778022
1403637236888318976 6.326776981 0.954056382 -1.819524050 -0.012565547 0.677495241 0.094517037 0.729320765
1403637236938319104 6.360075951 0.909388363 -1.715952396 -0.001437689 0.671980679 0.087798320 0.735344410
1403637236988318976 6.406581402 0.845400810 -1.599666595 0.008471642 0.667763352 0.081043363 0.739900231
1403637237038319104 6.426738262 0.788618088 -1.511700511 0.020377472 0.662588716 0.073995329 0.745040715
1403637237088318976 6.454338551 0.720262587 -1.394802570 0.030904507 0.658620000 0.068601586 0.748704493
1403637237138319104 6.481997967 0.631559610 -1.270464063 0.040653381 0.654201567 0.065371662 0.752392292
1403637237188318976 6.489136219 0.588052273 -1.173698425 0.051112719 0.646766901 0.063184582 0.758345366
1403637237238319104 6.498042583 0.535124302 -1.065653920 0.057449475 0.639096141 0.062956117 0.764390111
1403637237288318976 6.489723682 0.461419195 -0.959593534 0.058747612 0.631250560 0.065544821 0.770568192
1403637237338319104 6.480343819 0.416158140 -0.861206174 0.060210314 0.623814642 0.065703996 0.776474714
1403637237388318976 6.465331078 0.348497748 -0.758620739 0.060364559 0.617112994 0.068110771 0.781593621
1403637237438319104 6.447487354 0.278048545 -0.655362606 0.060984109 0.611352682 0.070064448 0.785887897
1403637237488318976 6.419274330 0.215372980 -0.562755346 0.060802527 0.606397450 0.070911266 0.789656162
1403637237538319104 6.383870125 0.152650565 -0.459795713 0.062303025 0.602036774 0.072916709 0.792687297
1403637237588318976 6.338569641 0.079004750 -0.368815541 0.062196922 0.598207057 0.075206228 0.795376539
1403637237638319104 6.294923782 0.034396216 -0.287681103 0.068009019 0.593247592 0.078385070 0.798303127
1403637237688318976 6.243034840 -0.046568960 -0.191775560 0.070285231 0.590129852 0.082302809 0.800020635
1403637237738319104 6.187124252 -0.107131995 -0.105619669 0.073573545 0.586777270 0.087090939 0.801682293
1403637237788318976 6.120334625 -0.182920694 -0.025254726 0.074103832 0.584061682 0.092422642 0.803018451
1403637237838319104 6.056423664 -0.242513165 0.054123640 0.074346460 0.582735777 0.099411733 0.803124487
1403637237888318976 5.983706951 -0.295742273 0.125841260 0.073569134 0.582574606 0.107648939 0.802250624
1403637237938319104 5.914133072 -0.357718170 0.208805680 0.071632624 0.584569752 0.116905361 0.799674988
1403637237988318976 5.839305878 -0.412472606 0.274451613 0.068890125 0.587592959 0.127243817 0.796114147
1403637238038319104 5.763367653 -0.456666172 0.354265213 0.067206129 0.591838896 0.138900980 0.791148901
1403637238088318976 5.684201717 -0.500200272 0.417212129 0.066608608 0.595525563 0.154590726 0.785502613
1403637238138319104 5.609814644 -0.549313009 0.465725899 0.064988807 0.599578023 0.168649450 0.779640973
1403637238188318976 5.524424076 -0.600736797 0.516229510 0.064779535 0.605308712 0.183201224 0.771908224
1403637238238319104 5.431364059 -0.618121147 0.570330262 0.069882303 0.612492383 0.197783217 0.762136042
1403637238288318976 5.353645325 -0.655645728 0.615646780 0.073370919 0.620297611 0.212423697 0.751481056
1403637238338319104 5.272279263 -0.684428394 0.653960109 0.077105440 0.628535986 0.226182327 0.740161359
1403637238388318976 5.187233925 -0.724000573 0.703604996 0.082079478 0.639687896 0.238442168 0.726090670
1403637238438319104 5.106118679 -0.754196525 0.714704096 0.086235300 0.648798048 0.249698982 0.713635087
1403637238488318976 5.019011497 -0.781111836 0.750000298 0.091677003 0.660815418 0.258900851 0.698490262
1403637238538319104 4.932539940 -0.792172074 0.768929720 0.095760562 0.672302127 0.266630024 0.683921218
1403637238588318976 4.852613449 -0.825838089 0.786305428 0.096382946 0.683556497 0.275905073 0.668832719
1403637238638319104 4.770322800 -0.845060229 0.783941329 0.096015044 0.690060854 0.289067984 0.656533957
1403637238688318976 4.679292679 -0.863905668 0.780266285 0.090330519 0.695169210 0.303158581 0.645503700
1403637238738319104 4.588038445 -0.880426168 0.774305999 0.083381735 0.697866559 0.319362521 0.635639310
1403637238788318976 4.508048534 -0.894275665 0.760175765 0.074746139 0.699171305 0.335805953 0.626743019
1403637238838319104 4.420833588 -0.910513520 0.748409450 0.065220699 0.700120091 0.351637155 0.618004382
1403637238888318976 4.337080479 -0.905892491 0.713624716 0.055718619 0.699044824 0.365822524 0.611886859
1403637238938319104 4.253021240 -0.902013421 0.673480868 0.045768712 0.697422981 0.379902571 0.605954170
1403637238988318976 4.180366516 -0.901282310 0.625821590 0.035659984 0.696464777 0.390752643 0.600814164
1403637239038319104 4.112484932 -0.902636051 0.573412418 0.024183178 0.698710442 0.393883646 0.596719801
1403637239088318976 4.044362545 -0.897411346 0.507571459 0.013862886 0.702338874 0.391893208 0.594093919
1403637239138319104 3.981751204 -0.895314217 0.430698395 0.005349977 0.709776759 0.381761402 0.591985285
1403637239188318976 3.931509256 -0.895097494 0.346120745 -0.001676342 0.718817651 0.368397832 0.589560330
1403637239238319104 3.888988018 -0.889538407 0.264978349 -0.004476999 0.729445279 0.353099108 0.585841775
1403637239288318976 3.841338873 -0.874678612 0.165904522 -0.003955972 0.738096774 0.341181427 0.582059026
1403637239338319104 3.810395002 -0.861841202 0.077459306 -0.004113166 0.746838450 0.332774043 0.575740218
1403637239388318976 3.773618698 -0.852880716 -0.027518064 -0.001703247 0.753853381 0.328867674 0.568812966
1403637239438319104 3.748709679 -0.827306747 -0.131111503 0.000887888 0.761391282 0.326037973 0.560340762
1403637239488318976 3.710186481 -0.823884606 -0.232699752 0.002888198 0.769342601 0.324932277 0.550020576
1403637239538319104 3.690877676 -0.793822765 -0.346209884 0.005781179 0.777860999 0.322453171 0.539372563
1403637239588318976 3.668223619 -0.750448465 -0.452292740 0.009265171 0.786995411 0.320387125 0.527166486
1403637239638319104 3.658397436 -0.714749455 -0.548066318 0.009888364 0.796438575 0.318302363 0.514073431
1403637239688318976 3.639855623 -0.684409857 -0.669039428 0.011083466 0.805206656 0.315613359 0.501903892
1403637239738319104 3.627050400 -0.630411267 -0.774835587 0.013302308 0.816908002 0.306944847 0.488128394
1403637239788318976 3.594129086 -0.592087507 -0.877546191 0.017151430 0.828552306 0.296965539 0.474360943
1403637239838319104 3.592243671 -0.522221684 -0.980177879 0.018739173 0.841526508 0.283298016 0.459591359
1403637239888318976 3.579867840 -0.467529058 -1.091146350 0.020663530 0.853153944 0.272653461 0.444253713
1403637239938319104 3.550740957 -0.424145699 -1.249804258 0.022909710 0.861352623 0.266355276 0.431974083
1403637239988318976 3.542706966 -0.408942819 -1.382428765 0.021689210 0.870385528 0.261612833 0.416554093
1403637240038319104 3.536397219 -0.336614728 -1.509361744 0.022378372 0.879080176 0.256391197 0.401224226
1403637240088318976 3.525728226 -0.261804104 -1.613509655 0.023797274 0.887095690 0.252797753 0.385471344
1403637240138319104 3.487221718 -0.172113776 -1.728503942 0.025957981 0.893737495 0.251157671 0.370781988
1403637240188318976 3.480260611 -0.115787387 -1.824144840 0.026103310 0.900438905 0.251631945 0.353849977
1403637240238319104 3.465558052 -0.084676623 -1.948160887 0.024051148 0.904631913 0.257249475 0.338947475
1403637240288318976 3.458140850 -0.027109861 -2.049453497 0.021469837 0.907870352 0.264737219 0.324383557
1403637240338319104 3.432759285 0.042737961 -2.150300026 0.017767129 0.909870446 0.271942168 0.312837988
1403637240388318976 3.416276932 0.109984159 -2.270180702 0.011998584 0.910583317 0.280510992 0.303327650
1403637240438319104 3.378683567 0.188675046 -2.390578270 0.004754798 0.910489500 0.288173020 0.296551138
1403637240488318976 3.376193285 0.237185597 -2.492182255 -0.002712457 0.910810649 0.295483172 0.288281620
1403637240538319104 3.368625164 0.289044857 -2.595613241 -0.008444689 0.911213458 0.300010085 0.282157004
1403637240588318976 3.351385593 0.332846999 -2.713455439 -0.010530727 0.911326706 0.302956730 0.278549701
1403637240638319104 3.324702263 0.394810081 -2.821975946 -0.012731859 0.911941051 0.302319825 0.277135402
1403637240688318976 3.321112633 0.435116410 -2.937243700 -0.015423585 0.912678957 0.301912189 0.275005996
1403637240738319104 3.304866314 0.490631580 -3.041715145 -0.014017192 0.913782597 0.299699336 0.273834318
1403637240788318976 3.305477142 0.528805614 -3.151821375 -0.015558050 0.915435791 0.295282483 0.273026556
1403637240838319104 3.305494785 0.580510378 -3.266714573 -0.018364299 0.918576479 0.284641176 0.273604482
1403637240888318976 3.296319485 0.610551357 -3.385996819 -0.016761212 0.921599925 0.273825526 0.274576426
1403637240938319104 3.303787231 0.645224094 -3.497131109 -0.017449372 0.924215496 0.264384836 0.274994373
1403637240988318976 3.294695377 0.691776395 -3.604255676 -0.016755715 0.925742030 0.257283300 0.276633680
1403637241038319104 3.298848867 0.734843731 -3.713615894 -0.015687853 0.925719321 0.256194174 0.277780682
1403637241088318976 3.288455486 0.781343460 -3.823518515 -0.013277386 0.924456120 0.258000374 0.280428976
1403637241138319104 3.302337646 0.809110880 -3.927256584 -0.014456877 0.923513412 0.260164648 0.281475246
1403637241188318976 3.292299271 0.864270687 -4.035533905 -0.014109294 0.922456563 0.260743797 0.284407318
1403637241238319104 3.303626537 0.907502770 -4.129435062 -0.017906208 0.922613561 0.259008855 0.285268158
1403637241288318976 3.309201241 0.943197012 -4.234704018 -0.022217663 0.922131836 0.258825928 0.286685139
1403637241338319104 3.320825338 0.993428946 -4.333820343 -0.025165763 0.922247469 0.256305575 0.288329214
1403637241388318976 3.326174974 1.034227490 -4.428905964 -0.030421574 0.922442615 0.253673017 0.289523989
1403637241438319104 3.342387199 1.071145773 -4.520287514 -0.035238087 0.922541201 0.252209157 0.289942324
1403637241488318976 3.350260258 1.120374918 -4.615585804 -0.039674968 0.923032045 0.248236790 0.291232228
1403637241538319104 3.378629684 1.157034755 -4.703916550 -0.045530923 0.924215019 0.242618948 0.291358113
1403637241588318976 3.388541698 1.193366051 -4.791434288 -0.048811048 0.924583197 0.238793314 0.292815745
1403637241638319104 3.400706530 1.234034419 -4.875518322 -0.048594419 0.925417483 0.234188735 0.293933153
1403637241688318976 3.423599720 1.263333559 -4.961201191 -0.047797523 0.926464856 0.228569418 0.295185059
1403637241738319104 3.453460217 1.292389631 -5.040426254 -0.047360186 0.927774608 0.222583205 0.295716137
1403637241788318976 3.473443270 1.322784305 -5.108736515 -0.045716431 0.929196239 0.215985462 0.296402901
1403637241838319104 3.498762846 1.346459031 -5.179467678 -0.041719623 0.930243015 0.211100653 0.297227144
1403637241888318976 3.529764891 1.367622495 -5.248444080 -0.032983370 0.930989027 0.208456203 0.297854871
1403637241938319104 3.560839176 1.384136200 -5.310584545 -0.020276582 0.931575716 0.205785751 0.299011379
1403637241988318976 3.589646339 1.403925538 -5.370295048 -0.010888460 0.932101965 0.202307612 0.300231695
1403637242038319104 3.616515636 1.421427011 -5.421836376 -0.005299820 0.932841659 0.198833331 0.300405741
1403637242088318976 3.639456034 1.426764369 -5.476722240 -0.005741373 0.932944953 0.198707074 0.300160408
1403637242138319104 3.667309761 1.436910868 -5.525360107 -0.009317000 0.933047235 0.199678063 0.299106628
1403637242188318976 3.692619562 1.448538303 -5.567186356 -0.014953175 0.933041751 0.201040283 0.297980309
1403637242238319104 3.730017424 1.452630162 -5.606626034 -0.020771099 0.933310270 0.201942399 0.296175212
1403637242288318976 3.751171589 1.458601594 -5.645569801 -0.025362039 0.933329821 0.202158496 0.295608014
1403637242338319104 3.786185026 1.460783243 -5.677011490 -0.032622024 0.934230864 0.199917510 0.293566734
1403637242388318976 3.801304817 1.463299990 -5.705070972 -0.038619913 0.934863746 0.196800902 0.292929500
1403637242438319104 3.835219860 1.472269058 -5.728419304 -0.043685429 0.936080933 0.192067415 0.291469067
1403637242488318976 3.869864225 1.469555140 -5.749117851 -0.048952531 0.936838329 0.188992456 0.290205717
1403637242538319104 3.898669720 1.480676293 -5.762796402 -0.049900796 0.937368155 0.185280681 0.290726453
1403637242588318976 3.926817656 1.483733773 -5.772025108 -0.048710596 0.937075853 0.182602942 0.293551147
1403637242638319104 3.960660934 1.484274149 -5.773897648 -0.046286475 0.935711801 0.182185143 0.298512220
1403637242688318976 3.988127947 1.479130149 -5.774103642 -0.043407410 0.933263123 0.182830647 0.306118757
1403637242738319104 4.031378746 1.472576857 -5.767996788 -0.038705282 0.930345476 0.184041828 0.314782113
1403637242788318976 4.064208508 1.463198185 -5.755282402 -0.031139683 0.927237272 0.185182661 0.323988765
1403637242838319104 4.100763321 1.443615079 -5.738371849 -0.024140004 0.924613833 0.184922129 0.332130015
1403637242888318976 4.141208649 1.437530756 -5.716086864 -0.017150771 0.922524810 0.183472648 0.339104056
1403637242938319104 4.180114269 1.413690686 -5.698168755 -0.015648905 0.920640290 0.181212485 0.345454216
1403637242988318976 4.213920116 1.392716527 -5.673410892 -0.014542923 0.919292688 0.177787587 0.350829035
1403637243038319104 4.234571457 1.384594202 -5.639329433 -0.014889520 0.917833567 0.176268503 0.355372012
1403637243088318976 4.262136459 1.362849593 -5.604483604 -0.018946400 0.916467011 0.176638111 0.358508348
1403637243138319104 4.293811321 1.347648621 -5.569524288 -0.022969395 0.915269792 0.177652702 0.360822856
1403637243188318976 4.327223301 1.331503868 -5.525800228 -0.025207086 0.913392961 0.182770923 0.362867355
1403637243238319104 4.354117870 1.318994284 -5.477195740 -0.025137894 0.911313772 0.189023033 0.364891201
1403637243288318976 4.389872074 1.306363106 -5.434414387 -0.023832871 0.909561455 0.194554582 0.366440207
1403637243338319104 4.417228699 1.289367914 -5.377396584 -0.023129690 0.907987297 0.199743062 0.367596000
1403637243388318976 4.440626144 1.274183869 -5.324527264 -0.021197313 0.906830668 0.203453079 0.368531883
1403637243438319104 4.478173256 1.263564587 -5.268164635 -0.019289065 0.906189620 0.206166998 0.368705124
1403637243488318976 4.506038189 1.243425846 -5.206248283 -0.018666979 0.906004906 0.207318962 0.368545145
1403637243538319104 4.533123016 1.233859181 -5.146432400 -0.016186016 0.905426502 0.209747195 0.368709892
1403637243588318976 4.563606262 1.212580800 -5.085500717 -0.014342984 0.903741121 0.216076419 0.369265765
1403637243638319104 4.591007710 1.202081442 -5.027457714 -0.011051411 0.902134657 0.221625760 0.370017529
1403637243688318976 4.621055126 1.169457912 -4.961490154 -0.010112594 0.900053442 0.230321750 0.369801760
1403637243738319104 4.645566940 1.130464315 -4.883031368 -0.007108580 0.899113536 0.236342520 0.368356496
1403637243788318976 4.673573494 1.114950299 -4.819532394 -0.001226914 0.896746337 0.243977427 0.369214654
1403637243838319104 4.706442356 1.083307981 -4.755506516 0.006347123 0.894364059 0.254059643 0.368139088
1403637243888318976 4.727848530 1.061041474 -4.692845345 0.011158091 0.892637432 0.259886771 0.368147701
1403637243938319104 4.751795769 1.025138855 -4.636869907 0.015843445 0.890595913 0.266161293 0.368437380
1403637243988318976 4.782797337 0.984970927 -4.570737839 0.016815174 0.890756309 0.268278778 0.366465509
1403637244038319104 4.810297966 0.956235170 -4.518318176 0.017389705 0.890765369 0.268318653 0.366387337
1403637244088318976 4.838293076 0.917271018 -4.457231522 0.017669190 0.891481340 0.268618315 0.364407659
1403637244138319104 4.853702068 0.877377510 -4.400384426 0.016286885 0.892164946 0.267545611 0.363587379
1403637244188318976 4.879072666 0.837438822 -4.348496437 0.016470719 0.893199623 0.266554892 0.361761838
1403637244238319104 4.891698837 0.799367666 -4.292429447 0.017015269 0.894121647 0.264792174 0.360752106
1403637244288318976 4.919801712 0.753018379 -4.252779007 0.016474348 0.893646061 0.266514212 0.360687464
1403637244338319104 4.933805466 0.707197666 -4.200232506 0.016132740 0.893621504 0.268389761 0.359370708
1403637244388318976 4.959553719 0.664855480 -4.146635532 0.015628034 0.892869353 0.270869404 0.359402001
1403637244438319104 4.978654385 0.621915817 -4.103046417 0.014179167 0.891557634 0.272997528 0.361104220
1403637244488318976 4.993810177 0.570626974 -4.064040184 0.010413727 0.889910221 0.274154186 0.364404768
1403637244538319104 5.009083748 0.523830414 -4.015983582 0.003768447 0.888981402 0.271959543 0.368423492
1403637244588318976 5.026616096 0.480104923 -3.983433247 -0.003400849 0.886953235 0.270438105 0.374387026
1403637244638319104 5.041506290 0.436421394 -3.943070889 -0.010696578 0.884998381 0.268981189 0.379884928
1403637244688318976 5.064331055 0.394677877 -3.905863285 -0.016861822 0.882226586 0.267419636 0.387141615
1403637244738319104 5.083964825 0.355364084 -3.863290310 -0.021276100 0.879577279 0.266037494 0.393846631
1403637244788318976 5.104761124 0.317236423 -3.821054220 -0.024335500 0.877133965 0.264870226 0.399859428
1403637244838319104 5.121665955 0.285668612 -3.792834520 -0.025704775 0.874463201 0.264267594 0.405975312
1403637244888318976 5.147328854 0.251340151 -3.751673937 -0.026987562 0.872442842 0.263513893 0.410701424
1403637244938319104 5.165681362 0.217606544 -3.719628334 -0.026292067 0.869758427 0.264763027 0.415607393
1403637244988318976 5.192947388 0.183729410 -3.671555281 -0.025811551 0.867750823 0.266638547 0.418624043
1403637245038319104 5.226055622 0.142786264 -3.636563778 -0.023001371 0.864858210 0.272831410 0.420778155
1403637245088318976 5.254098892 0.118744135 -3.605092049 -0.017071513 0.860721529 0.281702489 0.423687130
1403637245138319104 5.281632423 0.091879606 -3.575129032 -0.011402108 0.856734216 0.290943891 0.425709039
1403637245188318976 5.320136070 0.070774794 -3.526352406 -0.009530796 0.854723275 0.297203034 0.425473422
1403637245238319104 5.357950211 0.038825512 -3.496041775 -0.012306293 0.854608655 0.297151953 0.425668061
1403637245288318976 5.388636589 0.014580965 -3.479623795 -0.015851691 0.855798900 0.292378932 0.426463962
1403637245338319104 5.423075676 -0.002455950 -3.449460268 -0.020462425 0.857946634 0.286155105 0.426173806
1403637245388318976 5.462482929 -0.009819984 -3.417247534 -0.022796139 0.860116303 0.279691309 0.425973028
1403637245438319104 5.499362469 -0.031295300 -3.383433580 -0.026337756 0.861424863 0.274713218 0.426363885
1403637245488318976 5.535774231 -0.051711082 -3.368848801 -0.028876232 0.860791862 0.272114873 0.429135233
1403637245538319104 5.574206352 -0.077575684 -3.354500532 -0.029879209 0.858944774 0.271215260 0.433316737
1403637245588318976 5.609300137 -0.081470013 -3.341147900 -0.031335145 0.856810689 0.268978983 0.438798189
1403637245638319104 5.662825584 -0.096981049 -3.309025288 -0.032652393 0.854250968 0.268508017 0.443951130
1403637245688318976 5.704914093 -0.107944489 -3.282038212 -0.033798501 0.851173699 0.267041266 0.450610667
1403637245738319104 5.756088257 -0.127730131 -3.256830931 -0.033698071 0.847818971 0.264591128 0.458321869
1403637245788318976 5.801379681 -0.131254196 -3.236955643 -0.030151533 0.844414413 0.257864505 0.468573511
1403637245838319104 5.850067139 -0.132540941 -3.215606928 -0.026034473 0.841326535 0.247142121 0.480013132
1403637245888318976 5.909481049 -0.142075300 -3.204369068 -0.024293425 0.836014569 0.238756329 0.493441910
1403637245938319104 5.968589783 -0.138512611 -3.187397242 -0.020693125 0.829686046 0.230736494 0.507891178
1403637245988318976 6.013419628 -0.141616821 -3.137629747 -0.018530276 0.823553026 0.222541958 0.521432757
1403637246038319104 6.070132256 -0.152573347 -3.125233650 -0.019038396 0.814346671 0.216474682 0.538159609
1403637246088318976 6.112615585 -0.146909475 -3.106611013 -0.018841347 0.803872168 0.208518475 0.556735694
1403637246138319104 6.167213440 -0.142382622 -3.065833092 -0.018803125 0.793355048 0.200311765 0.574551523
1403637246188318976 6.233512878 -0.141687632 -3.055063725 -0.017924149 0.780430436 0.196402565 0.593323827
1403637246238319104 6.272079945 -0.135804534 -3.015761614 -0.016289191 0.767273426 0.189837933 0.612362504
1403637246288318976 6.327465057 -0.160804272 -2.981948376 -0.018465161 0.753359973 0.186151072 0.630440712
1403637246338319104 6.367284298 -0.174474716 -2.955341816 -0.019344628 0.738668263 0.180095538 0.649276972
1403637246388318976 6.406944752 -0.153006196 -2.917957783 -0.020949151 0.723413408 0.169422805 0.668976843
1403637246438319104 6.451482296 -0.144748569 -2.874799490 -0.025290763 0.709185004 0.158197001 0.686578989
1403637246488318976 6.512567520 -0.126957655 -2.879304171 -0.025995711 0.692218900 0.147657037 0.705942333
1403637246538319104 6.554459095 -0.134361982 -2.830628872 -0.026023995 0.677879393 0.138622701 0.721516430
1403637246588318976 6.575692177 -0.129237533 -2.792093277 -0.025796693 0.663775742 0.125669047 0.736846983
1403637246638319104 6.612044334 -0.109227419 -2.740963459 -0.023399472 0.649735868 0.114851989 0.751069069
1403637246688318976 6.656816483 -0.113756478 -2.720726967 -0.020093819 0.633731365 0.106133752 0.765974164
1403637246738319104 6.697247982 -0.098989725 -2.689997673 -0.018596491 0.618956208 0.096824363 0.779212713
1403637246788318976 6.730301380 -0.080001414 -2.664444923 -0.015249725 0.602870822 0.089408085 0.792666614
1403637246838319104 6.756334305 -0.091331244 -2.615497112 -0.016235964 0.588428199 0.082555704 0.804159939
1403637246888318976 6.779603958 -0.082209885 -2.554159641 -0.016291242 0.574431598 0.078105509 0.814654887
1403637246938319104 6.802346706 -0.091100812 -2.505439043 -0.020356284 0.560098231 0.077466451 0.824545026
1403637246988318976 6.817716599 -0.093598723 -2.463763475 -0.027039725 0.546462119 0.077569582 0.833445251
1403637247038319104 6.837038040 -0.086063862 -2.412688732 -0.030910322 0.535078883 0.078942962 0.840537429
1403637247088318976 6.844029427 -0.077891886 -2.364212513 -0.035398465 0.525901854 0.082151383 0.845828176
1403637247138319104 6.870237827 -0.085980833 -2.324071884 -0.039604921 0.516599953 0.087410353 0.850832164
1403637247188318976 6.883550644 -0.077880561 -2.290231943 -0.042402983 0.509958327 0.091218285 0.854297221
1403637247238319104 6.893694878 -0.104888797 -2.217105150 -0.046246555 0.506455958 0.096167020 0.855637550
1403637247288318976 6.913785934 -0.106407046 -2.177694321 -0.045469310 0.502440691 0.097621128 0.857878745
1403637247338319104 6.921721458 -0.103792131 -2.136954308 -0.038668010 0.500594437 0.095931821 0.859480739
1403637247388318976 6.917841911 -0.101797581 -2.068968058 -0.026709497 0.502833426 0.088567115 0.859418988
1403637247438319104 6.927968979 -0.092270911 -2.023704529 -0.012961696 0.503330052 0.081521548 0.860142469
1403637247488318976 6.941487312 -0.097006619 -1.975576639 -0.005866857 0.503447533 0.079039298 0.860383034
1403637247538319104 6.944407463 -0.086787730 -1.926700592 -0.003511388 0.503505111 0.077097796 0.860538304
1403637247588318976 6.945062160 -0.083629251 -1.876835823 -0.004058226 0.502153337 0.074988887 0.861511588
1403637247638319104 6.949930191 -0.077698380 -1.829173803 -0.004858650 0.499377936 0.072861016 0.863301456
1403637247688318976 6.948778152 -0.085920751 -1.780032635 -0.008030014 0.496748507 0.066842951 0.865279436
1403637247738319104 6.944378853 -0.082515150 -1.725396872 -0.010303585 0.493661731 0.060515460 0.867484748
1403637247788318976 6.931246758 -0.058848679 -1.674169779 -0.011982608 0.490002811 0.052773740 0.870039403
1403637247838319104 6.929328918 -0.068768561 -1.638531923 -0.014928696 0.483542591 0.046426021 0.873961270
1403637247888318976 6.916287899 -0.073843867 -1.582534552 -0.014537501 0.476940334 0.044634953 0.877681196
1403637247938319104 6.899423599 -0.074867666 -1.544356108 -0.010117940 0.467376083 0.043849822 0.882912457
1403637247988318976 6.872179031 -0.073098063 -1.493295431 -0.005068165 0.458580256 0.045152593 0.887490690
1403637248038319104 6.847794533 -0.076919794 -1.433512926 -0.004878887 0.449655503 0.049202487 0.891832530
1403637248088318976 6.808975220 -0.065592974 -1.384408236 -0.008064055 0.440930486 0.050998602 0.896054924
1403637248138319104 6.775351524 -0.078038484 -1.326625824 -0.014225706 0.431551456 0.054062512 0.900354505
1403637248188318976 6.736985683 -0.082137227 -1.280420780 -0.019595291 0.423218459 0.056483749 0.904052913
1403637248238319104 6.715271473 -0.099276453 -1.238178968 -0.027325066 0.414638788 0.058091097 0.907718837
1403637248288318976 6.682462692 -0.085569918 -1.192679167 -0.027830020 0.407473356 0.060938120 0.910756588
1403637248338319104 6.634777069 -0.095722288 -1.128856182 -0.031175101 0.404205382 0.061086833 0.912093461
1403637248388318976 6.579561234 -0.070458502 -1.059229136 -0.028143311 0.402943939 0.061581995 0.912716687
1403637248438319104 6.545777798 -0.080363065 -1.008763313 -0.027853087 0.399481565 0.062230069 0.914202452
1403637248488318976 6.510538578 -0.077336133 -0.953328133 -0.025352055 0.397734106 0.061108936 0.915112317
1403637248538319104 6.462190628 -0.072124034 -0.897243738 -0.019482598 0.397776484 0.058912389 0.915381670
1403637248588318976 6.402805328 -0.062315941 -0.831873894 -0.014393521 0.399860054 0.056384325 0.914727032
1403637248638319104 6.351483345 -0.054246634 -0.771219492 -0.013160972 0.401477367 0.055188078 0.914109886
1403637248688318976 6.312732220 -0.060077935 -0.725747824 -0.016903991 0.400961369 0.055832852 0.914235651
1403637248738319104 6.271022320 -0.066070259 -0.684271574 -0.021904921 0.401066571 0.057202570 0.913998723
1403637248788318976 6.223772049 -0.071720898 -0.634602785 -0.026844129 0.402214408 0.058800176 0.913260937
1403637248838319104 6.175610065 -0.077639550 -0.588616848 -0.029980315 0.403267622 0.060755156 0.912570655
1403637248888318976 6.132638931 -0.094365448 -0.546150684 -0.033049293 0.403776407 0.063423760 0.912057996
1403637248938319104 6.071259499 -0.115799010 -0.492489576 -0.034850560 0.405769438 0.066653430 0.910875380
1403637248988318976 6.029480934 -0.150015473 -0.451888561 -0.038081273 0.405899435 0.069153845 0.910501659
1403637249038319104 5.968166351 -0.146688312 -0.397372723 -0.035483137 0.408703148 0.068551585 0.909397244
1403637249088318976 5.921429157 -0.177185595 -0.357119799 -0.037650254 0.409182280 0.069428116 0.909028113
1403637249138319104 5.863586426 -0.191056490 -0.298934698 -0.035766337 0.411776990 0.070435107 0.907854259
1403637249188318976 5.809171677 -0.212246895 -0.254058123 -0.036727834 0.412925720 0.069781706 0.907344401
1403637249238319104 5.758943558 -0.222019166 -0.216084003 -0.034569513 0.412633270 0.069528423 0.907581687
1403637249288318976 5.707846642 -0.242793024 -0.166501045 -0.032681204 0.413311779 0.070236392 0.907288373
1403637249338319104 5.642496109 -0.283157110 -0.107973576 -0.033132773 0.416187048 0.069413409 0.906020045
1403637249388318976 5.588213921 -0.293591708 -0.062181711 -0.031802643 0.416551858 0.069613643 0.905884683
1403637249438319104 5.536156178 -0.322613686 -0.018504858 -0.032301676 0.415665954 0.071093887 0.906158984
1403637249488318976 5.477788448 -0.340718061 0.047906399 -0.032255586 0.417577654 0.071084961 0.905281961
1403637249538319104 5.417306900 -0.338833272 0.098810911 -0.031119630 0.417622358 0.071337849 0.905281186
1403637249588318976 5.360431671 -0.344092280 0.153069735 -0.030673452 0.417439520 0.071948968 0.905332386
1403637249638319104 5.303034782 -0.356859744 0.207186460 -0.031465117 0.417158037 0.072527297 0.905388832
1403637249688318976 5.244536400 -0.345907480 0.269575119 -0.028668581 0.418241322 0.070311882 0.905156612
1403637249738319104 5.187645912 -0.333677828 0.316150427 -0.022800285 0.416945726 0.068296902 0.906075001
1403637249788318976 5.125196457 -0.340637982 0.372514009 -0.019227976 0.416661620 0.066324130 0.906435072
1403637249838319104 5.072893620 -0.333516181 0.425909042 -0.014817757 0.414510280 0.063109435 0.907732844
1403637249888318976 5.010692596 -0.340077490 0.480342627 -0.013148080 0.411075354 0.061999511 0.909395516
1403637249938319104 4.949007034 -0.342889160 0.529957533 -0.013211093 0.405980945 0.060790174 0.911761761
1403637249988318976 4.878685474 -0.352006942 0.578613997 -0.014660795 0.399446130 0.062480919 0.914507508
1403637250038319104 4.814611912 -0.358681947 0.633763790 -0.016033120 0.392592818 0.066715464 0.917149305
1403637250088318976 4.753152847 -0.366497964 0.681677580 -0.016849674 0.385160238 0.071495168 0.919921815
1403637250138319104 4.689743042 -0.369757295 0.727430344 -0.019518685 0.378385633 0.073468864 0.922521353
1403637250188318976 4.617855549 -0.383463502 0.773121238 -0.020569392 0.371880203 0.074667029 0.925044239
1403637250238319104 4.557273865 -0.391399413 0.816981077 -0.020408230 0.364009023 0.076784775 0.928000510
1403637250288318976 4.492061615 -0.399010420 0.865473509 -0.020250011 0.357378334 0.078306228 0.930450857
1403637250338319104 4.427276611 -0.405521065 0.913313627 -0.018569132 0.351453006 0.081385016 0.932476521
1403637250388318976 4.368653774 -0.412366539 0.961614966 -0.018671393 0.346565902 0.083078861 0.934152782
1403637250438319104 4.316934109 -0.409299463 1.002700329 -0.018409405 0.341616809 0.085800275 0.935733616
1403637250488318976 4.248346329 -0.417330027 1.044451833 -0.018734658 0.337832898 0.090521328 0.936655641
1403637250538319104 4.193690300 -0.420008779 1.088375926 -0.021272106 0.334755450 0.092805527 0.937482476
1403637250588318976 4.135925293 -0.411350727 1.128614545 -0.022090331 0.332195520 0.094506815 0.938203931
1403637250638319104 4.082426071 -0.420484543 1.162394285 -0.025344355 0.329353005 0.094043329 0.939169943
1403637250688318976 4.030861855 -0.426957071 1.202808857 -0.027141489 0.326690793 0.093362384 0.940116942
1403637250738319104 3.976363659 -0.430565834 1.235175610 -0.028198803 0.324602038 0.092424847 0.940901697
1403637250788318976 3.928780317 -0.438697189 1.274409175 -0.030031301 0.323424131 0.089941531 0.941491067
1403637250838319104 3.879305124 -0.447852075 1.306460500 -0.028990714 0.322013587 0.089690402 0.942031026
1403637250888318976 3.831706047 -0.460325778 1.334352136 -0.027473463 0.321005434 0.088723592 0.942511976
1403637250938319104 3.787557125 -0.474556178 1.365943670 -0.027496450 0.319744647 0.090492286 0.942771673
1403637250988318976 3.743565083 -0.485955030 1.395225286 -0.026263904 0.318847209 0.091237053 0.943039000
1403637251038319104 3.705904484 -0.499003738 1.420102000 -0.025898991 0.316526204 0.092068680 0.943749845
1403637251088318976 3.660497189 -0.520381868 1.445858836 -0.026931394 0.313330114 0.094160452 0.944580734
1403637251138319104 3.621465683 -0.537993073 1.466851592 -0.028365795 0.308517098 0.096663885 0.945869267
1403637251188318976 3.579680920 -0.556050658 1.494927406 -0.029207302 0.304777622 0.098666497 0.946848691
1403637251238319104 3.546269894 -0.578657687 1.514708400 -0.030280156 0.300804675 0.100087009 0.947935820
1403637251288318976 3.509779453 -0.601565063 1.533915639 -0.030115860 0.297343642 0.100330248 0.949006677
1403637251338319104 3.480395317 -0.626421571 1.550595522 -0.029590055 0.294064581 0.096087523 0.950482845
1403637251388318976 3.451083183 -0.653488755 1.564978719 -0.028385794 0.292256147 0.086643428 0.951983988
1403637251438319104 3.425208807 -0.679177999 1.578344107 -0.026921030 0.288078606 0.080950394 0.953799248
1403637251488318976 3.398222685 -0.704899430 1.597702622 -0.026154533 0.283628553 0.073892884 0.955725193
1403637251538319104 3.375985622 -0.730270505 1.610101342 -0.025251396 0.277491003 0.069131903 0.957904935
1403637251588318976 3.351156473 -0.751227021 1.624267578 -0.024754386 0.271268278 0.064156123 0.960044146
1403637251638319104 3.330654383 -0.776890934 1.637689114 -0.024549538 0.265250415 0.060737260 0.961951375
1403637251688318976 3.310227871 -0.793153167 1.651680470 -0.024167133 0.259158432 0.059020370 0.963726819
1403637251738319104 3.285770416 -0.810502470 1.664593220 -0.024096040 0.253960699 0.057789270 0.965185821
1403637251788318976 3.267929316 -0.825993776 1.674811125 -0.023485178 0.249706388 0.056339297 0.966395915
1403637251838319104 3.249133587 -0.841265976 1.687314510 -0.023588587 0.246718466 0.054082546 0.967289329
1403637251888318976 3.236882210 -0.854833186 1.700087309 -0.020815538 0.244574711 0.050782003 0.968075991
1403637251938319104 3.220160484 -0.867266476 1.707949400 -0.019063078 0.243734136 0.044258021 0.968644142
1403637251988318976 3.200537205 -0.880489051 1.720026970 -0.015730366 0.244145513 0.037113450 0.968900442
1403637252038319104 3.188366413 -0.889785469 1.724227428 -0.013285867 0.243815035 0.032791879 0.969176173
1403637252088318976 3.169071198 -0.899783790 1.734544039 -0.009899344 0.243640274 0.029214034 0.969375014
1403637252138319104 3.153352022 -0.907992184 1.739921093 -0.006601780 0.242990330 0.027677886 0.969611287
1403637252188318976 3.140781164 -0.915126145 1.746994257 -0.003418968 0.241545767 0.028667629 0.969959855
1403637252238319104 3.121905327 -0.918112695 1.750909805 -0.002041656 0.240374506 0.031132855 0.970178723
1403637252288318976 3.100932121 -0.922313929 1.752105951 -0.002193710 0.239341348 0.033168424 0.970366299
1403637252338319104 3.087200165 -0.925431669 1.758875132 -0.003658075 0.238397256 0.035530064 0.970510662
1403637252388318976 3.069319725 -0.919143736 1.761240244 -0.006724999 0.237655431 0.038152959 0.970576644
1403637252438319104 3.048840284 -0.917889118 1.764736295 -0.011604588 0.237334192 0.041463815 0.970473349
1403637252488318976 3.031834602 -0.911619246 1.765696526 -0.014933650 0.236998290 0.043449413 0.970423102
1403637252538319104 3.013064384 -0.903855145 1.766287327 -0.017842464 0.237035990 0.044529866 0.970315754
1403637252588318976 2.993845463 -0.892820299 1.765504122 -0.020010168 0.237124190 0.046260331 0.970170975
1403637252638319104 2.977336884 -0.883294702 1.761738658 -0.022379177 0.236684591 0.048763022 0.970103979
1403637252688318976 2.962777615 -0.871910572 1.759760857 -0.026952514 0.235762298 0.052410696 0.970022082
1403637252738319104 2.949631453 -0.866526961 1.760066986 -0.032252952 0.234428540 0.057202078 0.969912827
1403637252788318976 2.930887699 -0.852983892 1.760266900 -0.036738154 0.233567879 0.062356431 0.969643235
1403637252838319104 2.918224335 -0.847175717 1.752588868 -0.040356569 0.233470425 0.063450582 0.969451845
1403637252888318976 2.906868458 -0.841185689 1.750920653 -0.039763670 0.234963626 0.060267273 0.969318748
1403637252938319104 2.893915415 -0.833071947 1.750496030 -0.035484158 0.237066999 0.055496547 0.969257534
1403637252988318976 2.888735294 -0.833108068 1.743721724 -0.032839686 0.238706023 0.050233319 0.969235599
1403637253038319104 2.886316538 -0.837286174 1.733469725 -0.030472931 0.239791930 0.046462916 0.969232917
1403637253088318976 2.878299713 -0.834629655 1.727193117 -0.027842281 0.240474463 0.044631038 0.969229043
1403637253138319104 2.870421410 -0.839829445 1.719516873 -0.026270634 0.241568029 0.042684950 0.969088614
1403637253188318976 2.863409042 -0.837217093 1.711117268 -0.025128633 0.241966099 0.041967887 0.969050884
1403637253238319104 2.859874725 -0.842587709 1.704729557 -0.024177045 0.242392689 0.041451979 0.968990684
1403637253288318976 2.848090887 -0.840410769 1.702720165 -0.024102645 0.243528351 0.041237645 0.968716919
1403637253338319104 2.839961052 -0.836851120 1.692174673 -0.024235191 0.243211344 0.042428512 0.968741834
1403637253388318976 2.833944321 -0.832899034 1.683166265 -0.023966117 0.243846029 0.041562889 0.968626499
1403637253438319104 2.829435349 -0.825054944 1.675839543 -0.022793863 0.243184671 0.043554228 0.968733549
1403637253488318976 2.827312946 -0.819051206 1.664685249 -0.022409089 0.243404210 0.042786900 0.968721569
1403637253538319104 2.822658062 -0.811312199 1.657509804 -0.024041576 0.243754089 0.042365793 0.968612969
1403637253588318976 2.813758373 -0.803947985 1.650603056 -0.024420297 0.244290024 0.041997507 0.968484521
1403637253638319104 2.809476614 -0.797244787 1.642132640 -0.025015065 0.244833604 0.040033519 0.968415260
1403637253688318976 2.802692890 -0.786600649 1.630461454 -0.024247412 0.245588437 0.037526902 0.968343973
1403637253738319104 2.796334267 -0.785562158 1.621588945 -0.024282126 0.246344581 0.035587348 0.968224287
1403637253788318976 2.792475224 -0.782987535 1.608849525 -0.023156423 0.247198492 0.032132339 0.968155026
1403637253838319104 2.782967567 -0.777198076 1.597335458 -0.022876970 0.247891754 0.031145725 0.968016624
1403637253888318976 2.776606560 -0.778033674 1.582232356 -0.022620264 0.247978553 0.030072320 0.968034387
1403637253938319104 2.768436193 -0.778576672 1.570850611 -0.022420267 0.248051032 0.030074358 0.968020439
1403637253988318976 2.757974148 -0.777755141 1.562818766 -0.022463311 0.248687506 0.029502820 0.967873693
1403637254038319104 2.748489857 -0.785059273 1.542698026 -0.022079207 0.249118909 0.027446175 0.967832088
1403637254088318976 2.737252951 -0.790072858 1.530831814 -0.021452552 0.248872817 0.027327653 0.967912853
1403637254138319104 2.726556301 -0.795766234 1.510116458 -0.020545909 0.246810272 0.026011512 0.968496740
1403637254188318976 2.715194941 -0.802511811 1.493057966 -0.020979965 0.243505061 0.025622437 0.969334066
1403637254238319104 2.703714132 -0.808080614 1.477410316 -0.022951679 0.239366040 0.023867283 0.970364630
1403637254288318976 2.687011242 -0.818755031 1.458456635 -0.026131103 0.235042423 0.022017751 0.971384287
1403637254338319104 2.680336952 -0.822119594 1.437373281 -0.029147964 0.229863986 0.020777434 0.972564280
1403637254388318976 2.659267664 -0.832140625 1.416951060 -0.032602571 0.225490972 0.019751979 0.973499238
1403637254438319104 2.644948483 -0.841918945 1.399060488 -0.034926087 0.221401408 0.019669570 0.974358559
1403637254488318976 2.625513792 -0.851396739 1.380090475 -0.037991632 0.218587637 0.018244499 0.974906743
1403637254538319104 2.610707045 -0.853383303 1.361624241 -0.039270960 0.214880541 0.017877903 0.975686669
1403637254588318976 2.598073483 -0.856511712 1.347665548 -0.038903449 0.212342694 0.016883900 0.976274550
1403637254638319104 2.578404427 -0.863576651 1.331393957 -0.038178772 0.210341215 0.016581677 0.976741493
1403637254688318976 2.562199831 -0.859240174 1.317458868 -0.036741171 0.208935857 0.015204882 0.977120578
1403637254738319104 2.544515610 -0.862603545 1.303882122 -0.034403868 0.207720175 0.013678805 0.977487385
1403637254788318976 2.530200005 -0.861917496 1.287558317 -0.031487256 0.206356332 0.013997137 0.977869987
1403637254838319104 2.507095814 -0.858047664 1.276130438 -0.028911363 0.205283776 0.015113336 0.978158593
1403637254888318976 2.495360136 -0.857469678 1.263825655 -0.026986985 0.204269633 0.015032006 0.978427112
1403637254938319104 2.477301359 -0.851351380 1.247228146 -0.025066175 0.203526318 0.015677640 0.978622973
1403637254988318976 2.463657379 -0.844577372 1.235574841 -0.022744225 0.203288063 0.015167297 0.978737235
1403637255038319104 2.442116737 -0.836149156 1.226891041 -0.022890028 0.202874422 0.014867275 0.978824258
1403637255088318976 2.418274879 -0.831960022 1.211550832 -0.022032464 0.200765550 0.013940157 0.979292333
1403637255138319104 2.398679495 -0.821754217 1.196508765 -0.022012195 0.196852028 0.014275381 0.980082095
1403637255188318976 2.378108978 -0.818818808 1.179019451 -0.022426030 0.192407608 0.012659041 0.980977118
1403637255238319104 2.357077122 -0.812242568 1.164156795 -0.022093918 0.187533915 0.012030941 0.981935918
1403637255288318976 2.334021568 -0.807581902 1.151137829 -0.021472493 0.182929218 0.011369354 0.982825816
1403637255338319104 2.313480854 -0.810079455 1.132440805 -0.020692071 0.178301916 0.010735680 0.983699679
1403637255388318976 2.293658733 -0.803265691 1.107675076 -0.021335151 0.172463715 0.011245166 0.984720588
1403637255438319104 2.272865057 -0.800706267 1.084538460 -0.022066040 0.166963279 0.009861731 0.985666811
1403637255488318976 2.247238398 -0.800436616 1.067786098 -0.023592550 0.160975903 0.007481965 0.986647964
1403637255538319104 2.222463608 -0.793329775 1.052727461 -0.024368271 0.154503182 0.004327111 0.987682223
1403637255588318976 2.205539227 -0.788658679 1.027485490 -0.025504477 0.147128612 0.000204249 0.988788486
1403637255638319104 2.171116829 -0.780123472 1.019187212 -0.025724331 0.140276730 -0.003487459 0.989771962
1403637255688318976 2.150388718 -0.767601490 0.999292493 -0.027528901 0.131846949 -0.007902160 0.990856230
1403637255738319104 2.128227711 -0.756874382 0.978829980 -0.029757239 0.122623526 -0.011483576 0.991940558
1403637255788318976 2.104693174 -0.750221550 0.959393382 -0.032611188 0.113182627 -0.015995478 0.992910028
1403637255838319104 2.080604315 -0.744566321 0.928863525 -0.035660304 0.102904737 -0.019703707 0.993856490
1403637255888318976 2.051990032 -0.733457267 0.915366530 -0.037815437 0.092773855 -0.022721594 0.994709373
1403637255938319104 2.027083397 -0.731404066 0.889371514 -0.038885549 0.082632624 -0.026266199 0.995474696
1403637255988318976 2.006838083 -0.729929090 0.862868547 -0.040169962 0.073098563 -0.028026277 0.996121228
1403637256038319104 1.977834940 -0.735034049 0.841346979 -0.041139606 0.065816946 -0.031292807 0.996492088
1403637256088318976 1.952469110 -0.734826863 0.819254398 -0.041931711 0.059909448 -0.034105353 0.996739388
1403637256138319104 1.929671049 -0.738198042 0.794631720 -0.041222896 0.054805338 -0.036370974 0.996982574
1403637256188318976 1.898179770 -0.739724874 0.778628707 -0.038895339 0.051579610 -0.038050801 0.997185469
1403637256238319104 1.869479418 -0.747104406 0.754470944 -0.035395037 0.048839435 -0.039328154 0.997404218
1403637256288318976 1.843655229 -0.745688081 0.732728481 -0.033142518 0.046584398 -0.039568573 0.997579992
1403637256338319104 1.812422037 -0.747200012 0.714277983 -0.031634852 0.045653645 -0.040888581 0.997618735
1403637256388318976 1.779382229 -0.745569110 0.699975848 -0.030078759 0.045420811 -0.041549832 0.997650146
1403637256438319104 1.755493402 -0.737998247 0.679308057 -0.029095804 0.045264896 -0.042773973 0.997634649
1403637256488318976 1.726391673 -0.739362061 0.655864716 -0.028852403 0.045957122 -0.043944381 0.997559190
1403637256538319104 1.696340442 -0.731212497 0.635784149 -0.027573880 0.046313044 -0.042736325 0.997631431
1403637256588318976 1.663088441 -0.724123120 0.618945837 -0.027762650 0.047216173 -0.042643487 0.997587800
1403637256638319104 1.638699532 -0.714454591 0.594803333 -0.030658221 0.047890406 -0.040745158 0.997550189
1403637256688318976 1.610226274 -0.699204385 0.575097501 -0.035139211 0.047127541 -0.034825206 0.997662961
1403637256738319104 1.582420826 -0.687483251 0.548867226 -0.041284274 0.046078753 -0.027578069 0.997703254
1403637256788318976 1.546669602 -0.672184289 0.535298645 -0.045706905 0.045816366 -0.020492561 0.997693241
1403637256838319104 1.514953732 -0.660624921 0.516668916 -0.047720756 0.045544010 -0.014291633 0.997719526
1403637256888318976 1.481673717 -0.649247348 0.499635160 -0.047707494 0.045102641 -0.012260298 0.997767210
1403637256938319104 1.459310889 -0.635703027 0.478968084 -0.044317134 0.043989994 -0.014970295 0.997936249
1403637256988318976 1.433042288 -0.624357402 0.464430213 -0.042507432 0.041558154 -0.017418610 0.998079479
1403637257038319104 1.400140643 -0.612473130 0.445864022 -0.039839812 0.038664676 -0.022556195 0.998202920
1403637257088318976 1.375032425 -0.607021928 0.430225432 -0.038198907 0.034967531 -0.027011408 0.998292804
1403637257138319104 1.346392751 -0.596396089 0.409171999 -0.036918730 0.031932063 -0.030717008 0.998335540
1403637257188318976 1.320377111 -0.592660844 0.396248758 -0.036218930 0.028593929 -0.033689480 0.998366475
1403637257238319104 1.291837692 -0.585495532 0.371805429 -0.036841452 0.025490224 -0.035749219 0.998356104
1403637257288318976 1.266275525 -0.583960176 0.350843489 -0.038257200 0.022193320 -0.037855998 0.998303950
1403637257338319104 1.236031413 -0.581534505 0.331550449 -0.039603543 0.019847063 -0.039932288 0.998219967
1403637257388318976 1.209196329 -0.583462596 0.308134794 -0.040855963 0.017402072 -0.042737465 0.998098910
1403637257438319104 1.183825970 -0.583205342 0.288958639 -0.041554503 0.015407008 -0.044434872 0.998028755
1403637257488318976 1.154481053 -0.583045185 0.270479411 -0.042064704 0.013912029 -0.045444533 0.997983873
1403637257538319104 1.130171776 -0.585265398 0.247793227 -0.042833779 0.012704278 -0.048788898 0.997809350
1403637257588318976 1.094491243 -0.582503438 0.233551994 -0.045253966 0.011716536 -0.048622154 0.997722745
1403637257638319104 1.067865968 -0.573131204 0.216412842 -0.047465913 0.010435364 -0.047387507 0.997693598
1403637257688318976 1.040571690 -0.566486835 0.193861321 -0.051842596 0.009010031 -0.045752916 0.997565985
1403637257738319104 1.009197354 -0.559144557 0.179380998 -0.054518159 0.007467306 -0.045488454 0.997448146
1403637257788318976 0.981443822 -0.550182641 0.163418174 -0.057795778 0.004194310 -0.044326816 0.997335076
1403637257838319104 0.954891920 -0.544392765 0.145271391 -0.061090328 0.000517537 -0.044998009 0.997117281
1403637257888318976 0.922059178 -0.530247927 0.137984931 -0.063370720 -0.003631770 -0.044858728 0.996974766
1403637257938319104 0.895324826 -0.523794174 0.119048208 -0.065543912 -0.009655276 -0.044681985 0.996802032
1403637257988318976 0.863319218 -0.509581804 0.113289125 -0.066217974 -0.015718449 -0.045632325 0.996637225
1403637258038319104 0.831081629 -0.498761386 0.108987555 -0.066928647 -0.023251392 -0.046947956 0.996381402
1403637258088318976 0.801754117 -0.489241034 0.099789493 -0.067061059 -0.031878687 -0.047745612 0.996095836
1403637258138319104 0.773944378 -0.483244926 0.091401443 -0.065450318 -0.041880205 -0.050643623 0.995689511
1403637258188318976 0.741698742 -0.477508813 0.087114260 -0.060868986 -0.051442269 -0.054907009 0.995305955
1403637258238319104 0.712327182 -0.472981483 0.081839651 -0.056322001 -0.060042195 -0.060973477 0.994738698
1403637258288318976 0.680962086 -0.469344765 0.079980753 -0.051095575 -0.067395404 -0.065249942 0.994278431
1403637258338319104 0.654268682 -0.465468645 0.074140973 -0.046945874 -0.074554898 -0.068606965 0.993745804
1403637258388318976 0.618961096 -0.460965306 0.070779495 -0.044793259 -0.080588862 -0.070672385 0.993229270
1403637258438319104 0.592021883 -0.455119997 0.067041337 -0.044468790 -0.086961895 -0.068879336 0.992832184
1403637258488318976 0.564345539 -0.448536962 0.062638916 -0.046459112 -0.092781276 -0.065384597 0.992450535
1403637258538319104 0.535085201 -0.438894749 0.057653703 -0.049774647 -0.097368792 -0.062135328 0.992058992
1403637258588318976 0.507348537 -0.427030861 0.057151258 -0.050767504 -0.100500025 -0.059965745 0.991829872
1403637258638319104 0.479408056 -0.414833218 0.059210420 -0.048627365 -0.102796979 -0.059950303 0.991702616
1403637258688318976 0.452355534 -0.405444860 0.057333440 -0.046523884 -0.103658862 -0.060379025 0.991687834
1403637258738319104 0.426761210 -0.394649774 0.058637537 -0.044539545 -0.104886010 -0.059939794 0.991676569
1403637258788318976 0.398011804 -0.378949046 0.065702468 -0.042243492 -0.105084792 -0.060608651 0.991715312
1403637258838319104 0.371126473 -0.365675449 0.072387874 -0.040260151 -0.105034761 -0.059978541 0.991841435
1403637258888318976 0.344555378 -0.354908794 0.067906246 -0.038876843 -0.105105206 -0.059207838 0.991935432
1403637258938319104 0.321078777 -0.347528249 0.064087868 -0.039007120 -0.105017416 -0.057522289 0.992038786
1403637258988318976 0.299947351 -0.337994576 0.068343833 -0.039010499 -0.105071172 -0.057030044 0.992061377
1403637259038319104 0.277739316 -0.334423780 0.063784346 -0.039547786 -0.105107516 -0.054098230 0.992200494
1403637259088318976 0.257412583 -0.331659287 0.062684678 -0.039501876 -0.103959836 -0.055339187 0.992254794
1403637259138319104 0.238054350 -0.331940025 0.062476434 -0.038624901 -0.103755243 -0.055445533 0.992304802
1403637259188318976 0.217159599 -0.335216582 0.062908351 -0.038707551 -0.103524335 -0.053881794 0.992411792
1403637259238319104 0.199184939 -0.341343254 0.059608847 -0.037780132 -0.102973752 -0.053200364 0.992541552
1403637259288318976 0.180863813 -0.348450392 0.054947756 -0.037427571 -0.102783635 -0.052192491 0.992628157
1403637259338319104 0.162708551 -0.354195923 0.050803058 -0.037907202 -0.102136485 -0.051427793 0.992716670
1403637259388318976 0.147187784 -0.359805614 0.047745787 -0.037928440 -0.101938546 -0.050036661 0.992807269
1403637259438319104 0.131739259 -0.363404751 0.045935251 -0.037194662 -0.102472156 -0.046039522 0.992973506
1403637259488318976 0.117370300 -0.367322594 0.042412166 -0.036788113 -0.103729077 -0.040617108 0.993094742
1403637259538319104 0.103481628 -0.372602940 0.034634069 -0.036833700 -0.104117721 -0.037079681 0.993190765
1403637259588318976 0.091083653 -0.373878568 0.031096332 -0.036823533 -0.104061924 -0.035940047 0.993238866
1403637259638319104 0.083255962 -0.375901729 0.027426459 -0.036010530 -0.103850514 -0.035758775 0.993297338
1403637259688318976 0.074012399 -0.375592738 0.023171321 -0.036553960 -0.102442913 -0.038887128 0.993306100
1403637259738319104 0.069735631 -0.372601718 0.025643067 -0.039010134 -0.101367980 -0.041775241 0.993205726
1403637259788318976 0.063774459 -0.370774209 0.021432208 -0.041699827 -0.099746250 -0.046227049 0.993063390
1403637259838319104 0.060487539 -0.367445946 0.019943865 -0.042988539 -0.098742776 -0.049321156 0.992959857
1403637259888318976 0.054953117 -0.366830409 0.015567986 -0.042303137 -0.099115126 -0.047393404 0.993046045
1403637259938319104 0.055382736 -0.364029229 0.015238954 -0.040258899 -0.100312300 -0.043632347 0.993183196
1403637259988318976 0.052752506 -0.359044343 0.012112221 -0.038481921 -0.100513600 -0.043134529 0.993255079
1403637260038319104 0.050513800 -0.352572769 0.010646213 -0.036371965 -0.099750832 -0.045432977 0.993308961
1403637260088318976 0.050805990 -0.346383363 0.006368676 -0.035429835 -0.098896101 -0.048606288 0.993278265
1403637260138319104 0.053431097 -0.340309083 0.004902508 -0.036029309 -0.098319612 -0.051494494 0.993168414
1403637260188318976 0.053359155 -0.330045760 0.003907111 -0.036616985 -0.097044349 -0.055518776 0.993055522
1403637260238319104 0.058293600 -0.318923205 0.002614826 -0.037998870 -0.095737107 -0.060936075 0.992812812
1403637260288318976 0.064416960 -0.309054703 0.004000980 -0.037900899 -0.095272057 -0.064375415 0.992644250
1403637260338319104 0.067396432 -0.298993886 0.001816187 -0.037815403 -0.094077244 -0.069566704 0.992411196
1403637260388318976 0.069021821 -0.286414415 0.001734212 -0.036386304 -0.092354961 -0.075917147 0.992160857
1403637260438319104 0.072708741 -0.275506377 -0.000415657 -0.035055716 -0.091133051 -0.081221759 0.991901636
1403637260488318976 0.074779041 -0.263676375 -0.002963390 -0.037586596 -0.091243535 -0.082224503 0.991716206
1403637260538319104 0.074941680 -0.249609277 -0.003541581 -0.042878222 -0.090753920 -0.083074190 0.991475582
1403637260588318976 0.073603146 -0.238234207 -0.011012919 -0.049330939 -0.090857267 -0.082472779 0.991216302
1403637260638319104 0.073957242 -0.224763408 -0.008173421 -0.054388057 -0.091486961 -0.080411047 0.991063118
1403637260688318976 0.072374143 -0.213612601 -0.009643346 -0.056766346 -0.091746479 -0.079053156 0.991015017
1403637260738319104 0.068787791 -0.203850731 -0.015199348 -0.056026150 -0.092786811 -0.076730154 0.991142869
1403637260788318976 0.064926676 -0.191618249 -0.014230799 -0.052584942 -0.092818946 -0.076914638 0.991314113
1403637260838319104 0.061172925 -0.179945871 -0.013370028 -0.047643982 -0.094100595 -0.075200312 0.991574526
1403637260888318976 0.055823334 -0.166879639 -0.013893982 -0.044036202 -0.094701394 -0.073946632 0.991778374
1403637260938319104 0.051382922 -0.155688494 -0.013252148 -0.039935309 -0.095353745 -0.072987661 0.991960526
1403637260988318976 0.046739500 -0.144399419 -0.013194952 -0.036563564 -0.095853604 -0.073199205 0.992026746
1403637261038319104 0.041491441 -0.131765991 -0.013476336 -0.036059611 -0.095958583 -0.072938606 0.992054224
1403637261088318976 0.035996702 -0.119338900 -0.013643930 -0.039377008 -0.096390463 -0.071901493 0.991961956
1403637261138319104 0.030212961 -0.106631279 -0.014340149 -0.045289125 -0.095878527 -0.072536461 0.991713047
1403637261188318976 0.024618715 -0.093707696 -0.014188621 -0.051488142 -0.095601872 -0.073436812 0.991370916
1403637261238319104 0.019128714 -0.083442070 -0.016171172 -0.057961129 -0.095501967 -0.073944993 0.990985334
1403637261288318976 0.012636892 -0.073466137 -0.016860485 -0.061317295 -0.095419683 -0.074439913 0.990754247
1403637261338319104 0.005758120 -0.066142596 -0.016454477 -0.059882518 -0.095438488 -0.074078850 0.990867257
1403637261388318976 -0.002030605 -0.061373111 -0.017084178 -0.055079617 -0.095801607 -0.072654180 0.991216242
1403637261438319104 -0.010536175 -0.056037217 -0.015556756 -0.050205436 -0.096713230 -0.069407202 0.991619170
1403637261488318976 -0.018601332 -0.053603128 -0.015641542 -0.047177758 -0.097938046 -0.066315986 0.991859138
1403637261538319104 -0.026369218 -0.050176930 -0.014385793 -0.049619496 -0.098443739 -0.064641893 0.991800487
1403637261588318976 -0.034021575 -0.046838950 -0.014550452 -0.055603780 -0.097921938 -0.065175682 0.991499722
1403637261638319104 -0.041017614 -0.044279531 -0.012835007 -0.062114049 -0.097030558 -0.067387462 0.991052926
1403637261688318976 -0.048474673 -0.043939933 -0.011498533 -0.066112667 -0.096261524 -0.068674900 0.990780830
1403637261738319104 -0.055918045 -0.045233559 -0.008347826 -0.066635735 -0.095301747 -0.070818722 0.990687609
1403637261788318976 -0.064959481 -0.049027000 -0.004972377 -0.062166944 -0.095196269 -0.070545264 0.991007686
1403637261838319104 -0.072353818 -0.053840313 -0.001038705 -0.055159140 -0.095374659 -0.070380218 0.991417050
1403637261888318976 -0.080782190 -0.057867333 0.004348314 -0.049159385 -0.095670022 -0.069084726 0.991795301
1403637261938319104 -0.089423016 -0.060708191 0.010381399 -0.044463299 -0.095540479 -0.068671890 0.992058039
1403637261988318976 -0.097457692 -0.060983013 0.016363982 -0.040717404 -0.095012024 -0.068239979 0.992299378
1403637262038319104 -0.105687611 -0.058890648 0.023067910 -0.037960067 -0.095412068 -0.065416567 0.992560446
1403637262088318976 -0.112856202 -0.054787718 0.029061167 -0.035274230 -0.095776655 -0.062913075 0.992786229
1403637262138319104 -0.120596588 -0.048134871 0.036404029 -0.035233598 -0.095743507 -0.060864355 0.992918551
1403637262188318976 -0.127258807 -0.038981773 0.042258836 -0.034464918 -0.096412882 -0.058122121 0.993045092
1403637262238319104 -0.133070618 -0.028605420 0.049399015 -0.033865228 -0.096223176 -0.055741213 0.993220627
1403637262288318976 -0.138269931 -0.017210925 0.055842608 -0.034556389 -0.095892146 -0.054918468 0.993274629
1403637262338319104 -0.141637236 -0.005303306 0.064161181 -0.011261472 -0.103756197 -0.028116606 0.994141519
1403637262388318976 -0.143673375 -0.008314118 0.049774297 -0.010086464 -0.095779940 -0.052761737 0.993952036
1403637262438319104 -0.146460012 -0.015332848 0.036178719 -0.023100795 -0.077957258 -0.050396074 0.995414078
1403637262488318976 -0.142690897 -0.012565329 0.035120361 -0.028936654 -0.067390904 -0.034757178 0.996701062
1403637262538319104 -0.131268591 -0.008878639 0.040740058 -0.014450188 -0.069455720 -0.023233766 0.997209728
1403637262588318976 -0.128351837 -0.009266208 0.038251191 -0.000362012 -0.068584770 -0.024134282 0.997353256
1403637262638319104 -0.126148432 -0.008437410 0.039672829 0.003212276 -0.067358352 -0.023684507 0.997442544
1403637262688318976 -0.119706020 -0.008297706 0.049728781 -0.009172204 -0.073650867 -0.014696307 0.997133613
1403637262738319104 -0.123680219 -0.011622525 0.048683319 -0.017844319 -0.067500308 -0.023134168 0.997291386
1403637262788318976 -0.123015374 -0.013670105 0.046007030 -0.011898884 -0.068136990 -0.022015957 0.997362077
1403637262838319104 -0.122898221 -0.013624107 0.045755208 -0.011711283 -0.068192467 -0.023514258 0.997326314
1403637262888318976 -0.124032192 -0.013687391 0.046049021 -0.013993038 -0.068866722 -0.022827402 0.997266471
1403637262938319104 -0.122786164 -0.013701373 0.044955518 -0.012386397 -0.067514114 -0.025090909 0.997325838
1403637262988318976 -0.123521045 -0.013715332 0.046119995 -0.013206170 -0.068771601 -0.022514464 0.997290909
1403637263038319104 -0.123185739 -0.013709684 0.045527570 -0.013127061 -0.068131723 -0.023839083 0.997305095
1403637263088318976 -0.123415500 -0.013860079 0.045608614 -0.013494278 -0.068195961 -0.023716833 0.997298717
1403637263138319104 -0.123478040 -0.013912596 0.045537967 -0.013384677 -0.068431407 -0.023078786 0.997299016
1403637263188318976 -0.123272181 -0.013828238 0.045596614 -0.013248312 -0.068042830 -0.023793148 0.997310638
1403637263238319104 -0.123441257 -0.013813401 0.045864079 -0.013592160 -0.068613134 -0.023009542 0.997285366
1403637263288318976 -0.123220295 -0.013570242 0.046055458 -0.013420898 -0.068341494 -0.023365449 0.997298062
1403637263338319104 -0.123078458 -0.013622639 0.045465089 -0.013351433 -0.068403468 -0.023254069 0.997297347
1403637263388318976 -0.123504803 -0.013766012 0.046085656 -0.013397329 -0.068449087 -0.023319356 0.997292101
1403637263438319104 -0.123366892 -0.013540443 0.046121903 -0.013315502 -0.068420202 -0.023483753 0.997291267
1403637263488318976 -0.123377182 -0.013600124 0.046159670 -0.013229631 -0.068249196 -0.024037747 0.997290969
1403637263538319104 -0.123443007 -0.013520478 0.046074726 -0.013214081 -0.068585880 -0.023015311 0.997292161
1403637263588318976 -0.123450473 -0.013696447 0.046075318 -0.013404870 -0.068168685 -0.023808856 0.997299612
1403637263638319104 -0.123378798 -0.013561331 0.045974575 -0.013339391 -0.068556525 -0.023174839 0.997288823
1403637263688318976 -0.123408161 -0.013372080 0.046242729 -0.013248460 -0.068223469 -0.023527533 0.997304618
1403637263738319104 -0.123463497 -0.013360744 0.045942057 -0.013151957 -0.067998700 -0.023781016 0.997315228
1403637263788318976 -0.123461552 -0.013461225 0.046088278 -0.013166738 -0.068447299 -0.022966748 0.997303426
1403637263838319104 -0.123411544 -0.013335322 0.045925889 -0.013275047 -0.068032011 -0.024107037 0.997303486
1403637263888318976 -0.123493716 -0.013257510 0.046016917 -0.013157656 -0.068302587 -0.023139680 0.997309446
1403637263938319104 -0.123336136 -0.013263687 0.046379983 -0.013231768 -0.068257920 -0.023483070 0.997303545
1403637263988318976 -0.123377390 -0.013312357 0.046109140 -0.013262964 -0.068186887 -0.023397578 0.997309983
1403637264038319104 -0.123327777 -0.013406184 0.046197273 -0.013315966 -0.068330929 -0.023267042 0.997302473
1403637264088318976 -0.123301946 -0.013279282 0.046175689 -0.013322871 -0.068256103 -0.023585021 0.997300029
1403637264138319104 -0.123463601 -0.013327863 0.046210714 -0.013255393 -0.068201944 -0.023363132 0.997309864
1403637264188318976 -0.123274840 -0.013325317 0.045985315 -0.013337208 -0.068176582 -0.023622150 0.997304380
1403637264238319104 -0.123425618 -0.013389363 0.046301212 -0.013355482 -0.068224870 -0.023314836 0.997308075
1403637264288318976 -0.123366989 -0.013366634 0.046071809 -0.013306936 -0.068183050 -0.023355072 0.997310638
1403637264338319104 -0.123283729 -0.013374284 0.046080850 -0.013332027 -0.068235911 -0.023633571 0.997300148
1403637264388318976 -0.123444214 -0.013275142 0.046218369 -0.013246755 -0.068353944 -0.023366066 0.997299492
1403637264438319104 -0.123377584 -0.013223859 0.046188354 -0.013209899 -0.068231098 -0.023510711 0.997304976
1403637264488318976 -0.123451903 -0.013333822 0.046220489 -0.013287641 -0.068155743 -0.023659902 0.997305572
1403637264538319104 -0.123398602 -0.013242155 0.046251245 -0.013238215 -0.068228096 -0.023358835 0.997308373
1403637264588318976 -0.123388834 -0.013290937 0.046145786 -0.013278008 -0.068198062 -0.023496130 0.997306705
1403637264638319104 -0.123403504 -0.013248487 0.046155244 -0.013204187 -0.068232365 -0.023314336 0.997309625
1403637264688318976 -0.123341948 -0.013243223 0.046190523 -0.013274598 -0.068277083 -0.023381798 0.997304022
1403637264738319104 -0.123407274 -0.013333703 0.046058882 -0.013453089 -0.068099715 -0.023584101 0.997308969
1403637264788318976 -0.123401210 -0.013359256 0.046057522 -0.013233034 -0.068256311 -0.023409531 0.997305334
1403637264838319104 -0.123398595 -0.013353196 0.046018016 -0.013421456 -0.068116128 -0.023605604 0.997307777
1403637264888318976 -0.123360448 -0.013304944 0.045823105 -0.013314185 -0.068292066 -0.023304127 0.997304320
1403637264938319104 -0.123477511 -0.013283050 0.045899712 -0.013277252 -0.068322115 -0.023310892 0.997302592
1403637264988318976 -0.123387545 -0.013273089 0.045943841 -0.013364055 -0.068250746 -0.023529241 0.997301161
1403637265038319104 -0.123743795 -0.013788188 0.046702333 -0.013481801 -0.068208531 -0.023619790 0.997300327
1403637265088318976 -0.123766206 -0.013770701 0.046828348 -0.013550557 -0.068183087 -0.023803748 0.997296751
1403637265138319104 -0.123454228 -0.013357040 0.045988198 -0.013389396 -0.068302080 -0.023341926 0.997301698
1403637265188318976 -0.123688236 -0.013778369 0.046758115 -0.013485522 -0.068146013 -0.023783382 0.997300684
1403637265238319104 -0.123654976 -0.013775437 0.046877660 -0.013459235 -0.068222143 -0.023729017 0.997297108
1403637265288318976 -0.123732395 -0.013804417 0.046774559 -0.013507236 -0.068123370 -0.023690851 0.997304142
1403637265338319104 -0.123495400 -0.013384872 0.045977298 -0.013415343 -0.068185374 -0.023503350 0.997305572
1403637265388318976 -0.123467326 -0.013417289 0.046025045 -0.013475372 -0.068242826 -0.023696641 0.997296214
1403637265438319104 -0.123487063 -0.013532645 0.045800164 -0.013453544 -0.068259604 -0.023332007 0.997304022
1403637265488318976 -0.123462185 -0.013419916 0.045909874 -0.013483787 -0.068185508 -0.023697315 0.997300029
================================================
FILE: Examples/Stereo/euroc_old/CameraTrajectory_MH04.txt
================================================
1403638127295097088 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 1.000000000
1403638127345096960 -0.000046169 -0.000011313 -0.000072234 0.000023853 0.000109670 0.000046414 1.000000000
1403638127395097088 -0.000216693 -0.000024159 0.000111614 -0.000353673 -0.000029627 0.000742598 0.999999642
1403638127445096960 -0.000121226 -0.000019147 -0.000044342 -0.000190943 0.000300626 -0.000031587 0.999999940
1403638127495097088 0.000001532 -0.000147361 -0.000115833 0.000143367 0.000485968 0.000271863 0.999999821
1403638127545096960 -0.000209903 -0.000103889 -0.000045437 -0.000048149 0.000117383 0.000181567 1.000000000
1403638127595097088 -0.000145295 0.000038170 -0.000026065 -0.000182308 0.000066853 0.000257535 0.999999940
1403638127645096960 -0.000092068 -0.000016213 0.000010279 -0.000305982 -0.000247802 0.000445285 0.999999821
1403638127695097088 -0.000171462 -0.000037858 -0.000108429 -0.000267258 0.000105463 -0.000217056 0.999999940
1403638127745096960 -0.000215250 0.000042602 -0.000057957 -0.000012651 -0.000322323 0.000531974 0.999999821
1403638127795097088 -0.000346875 0.000028766 -0.000119472 -0.000281989 -0.000049200 0.000244863 0.999999940
1403638127845096960 -0.000165166 -0.000056556 -0.000027730 -0.000371675 -0.000313370 0.000930132 0.999999464
1403638127895097088 -0.000340632 -0.000134649 -0.000091695 -0.000382511 -0.000321967 0.000800212 0.999999523
1403638127945096960 -0.000320000 -0.000086169 -0.000099710 -0.000303479 -0.000178269 0.000789493 0.999999642
1403638127995097088 -0.000318028 -0.000102534 0.000133613 -0.000565445 -0.000210933 0.000621953 0.999999642
1403638128045096960 -0.000268840 0.000033197 0.000045917 -0.000615102 -0.000033633 0.000270845 0.999999762
1403638128095097088 -0.000431349 -0.000058958 0.000174835 -0.000756564 0.000208396 0.000222560 0.999999642
1403638128145096960 -0.000468344 -0.000201555 0.000282197 -0.001099881 -0.000034484 0.000892532 0.999998987
1403638128195097088 -0.000586171 0.000323793 0.000126837 0.000117807 -0.000022368 0.003178245 0.999994934
1403638128245096960 -0.000468768 0.000315894 0.000187888 0.000178156 0.000009345 0.002701066 0.999996364
1403638128295097088 -0.000416421 0.000406534 0.000050998 0.000327017 -0.000150004 0.002611998 0.999996543
1403638128345096960 -0.000444875 0.000435632 0.000141442 0.000359261 0.000104042 0.002215469 0.999997497
1403638128395097088 -0.000327932 0.000427598 0.000226039 0.000416861 0.000073987 0.001972084 0.999997973
1403638128445096960 -0.000345310 0.000431439 0.000224145 0.000298899 0.000128955 0.002503223 0.999996841
1403638128495097088 -0.000339756 0.000325723 0.000035944 0.000176715 -0.000049202 0.002837798 0.999995947
1403638128545096960 -0.000342145 0.000307035 0.000035413 0.000079923 -0.000063139 0.002884491 0.999995828
1403638128595097088 -0.000282068 0.000368957 0.000084991 0.000200537 -0.000020512 0.002952275 0.999995649
1403638128645096960 -0.000283735 0.000345038 0.000285961 0.000154758 -0.000003873 0.002592893 0.999996662
1403638128695097088 -0.000492682 0.000229175 0.000095279 -0.000248423 0.000108260 0.003445085 0.999994040
1403638128745096960 -0.000699242 0.000124929 0.000427528 -0.000371531 0.000325745 0.004173622 0.999991179
1403638128795097088 -0.000562243 0.000075761 0.000537347 -0.000491913 0.000548047 0.003746258 0.999992669
1403638128845096960 -0.000601870 0.000121404 0.000684670 -0.000538616 0.001182533 0.003487034 0.999993086
1403638128895097088 -0.000564096 0.000176517 0.000652433 -0.000584388 0.001129645 0.003747822 0.999992192
1403638128945096960 -0.000283385 0.000259602 0.000563735 -0.000434624 0.001450725 0.002378247 0.999996066
1403638128995097088 -0.000299870 0.000218222 0.000543700 -0.000634549 0.001438816 0.002211270 0.999996305
1403638129045096960 -0.000188218 0.000047748 0.000740785 -0.000178810 0.001099301 0.001555285 0.999998152
1403638129095097088 -0.000315291 -0.000233900 0.000619947 -0.000020503 0.001962727 -0.001874306 0.999996305
1403638129145096960 -0.000466317 -0.001444575 0.000361865 0.000177777 0.002754582 -0.003810128 0.999988973
1403638129195097088 -0.000642297 -0.003709401 0.000079619 0.001436642 0.002641395 -0.004101526 0.999987066
1403638129245096960 -0.000346766 -0.007585238 -0.001941513 0.007236692 -0.000806606 0.005507345 0.999958277
1403638129295097088 -0.000017534 -0.014454804 -0.004901736 0.017192470 -0.004557943 0.022046849 0.999598682
1403638129345096960 0.001344736 -0.023274852 -0.008115806 0.029415946 -0.007251188 0.041056067 0.998697400
1403638129395097088 0.002563500 -0.031067446 -0.009307468 0.036825255 -0.010104756 0.057146262 0.997635245
1403638129445096960 0.003804957 -0.035279311 -0.011625168 0.036309317 -0.010868414 0.064672619 0.997186542
1403638129495097088 0.003566587 -0.037289158 -0.012594590 0.027054477 -0.011382524 0.059424911 0.997801185
1403638129545096960 0.002751668 -0.038145177 -0.013552219 0.015272189 -0.011419575 0.045681227 0.998774052
1403638129595097088 0.001563298 -0.039655559 -0.014352634 0.006148646 -0.010524384 0.030154008 0.999470949
1403638129645096960 0.000936616 -0.042660709 -0.015258325 0.001816353 -0.009178395 0.017938383 0.999795318
1403638129695097088 0.001040000 -0.048027765 -0.016778667 0.003388213 -0.007881664 0.011972963 0.999891520
1403638129745096960 0.000679358 -0.055366799 -0.019081272 0.007535679 -0.008173048 0.013668163 0.999844790
1403638129795097088 0.000638911 -0.063064754 -0.022998469 0.007461456 -0.009508584 0.015437584 0.999807775
1403638129845096960 -0.000010078 -0.071261257 -0.026332926 0.001800129 -0.010900389 0.013685063 0.999845326
1403638129895097088 -0.001350870 -0.081292309 -0.030438516 -0.004386916 -0.012497230 0.009757589 0.999864638
1403638129945096960 -0.002756550 -0.094669744 -0.035827946 -0.007665806 -0.013377607 0.005694158 0.999864936
1403638129995097088 -0.004130699 -0.111320809 -0.041465916 -0.003549753 -0.014634450 0.006843780 0.999863207
1403638130045096960 -0.004736095 -0.131090298 -0.047324613 0.004934246 -0.016023558 0.013090565 0.999773741
1403638130095097088 -0.005356560 -0.149909347 -0.054771505 0.012678451 -0.017775092 0.018918335 0.999582589
1403638130145096960 -0.006365289 -0.169806167 -0.062941253 0.016355593 -0.020423803 0.021281466 0.999431074
1403638130195097088 -0.006510204 -0.188485697 -0.070164949 0.016289674 -0.023856223 0.020454213 0.999373376
1403638130245096960 -0.007808964 -0.206746161 -0.077047139 0.016813951 -0.026330419 0.017903533 0.999351501
1403638130295097088 -0.008096453 -0.226411581 -0.088675648 0.020632118 -0.029283931 0.021641674 0.999123812
1403638130345096960 -0.008505208 -0.248296589 -0.096786678 0.026850773 -0.031423811 0.029643996 0.998705566
1403638130395097088 -0.008776120 -0.270593405 -0.108752549 0.031336218 -0.034183126 0.035841297 0.998281002
1403638130445096960 -0.013455039 -0.287800223 -0.108393043 0.033307813 -0.037616808 0.038167562 0.998007417
1403638130495097088 -0.022541456 -0.288416773 -0.117120832 0.032932725 -0.038957741 0.033308506 0.998142421
1403638130545096960 -0.023986397 -0.308158070 -0.128040642 0.030002931 -0.039106302 0.024854682 0.998475194
1403638130595097088 -0.024816116 -0.324123621 -0.133407325 0.030569494 -0.038585003 0.021779986 0.998550117
1403638130645096960 -0.021629736 -0.342115968 -0.140113980 0.035593405 -0.038591608 0.022295197 0.998372018
1403638130695097088 -0.023396291 -0.358369410 -0.147052765 0.042203791 -0.038848154 0.028693451 0.997941077
1403638130745096960 -0.028194871 -0.367476463 -0.148032144 0.049541797 -0.041577917 0.039521445 0.997123301
1403638130795097088 -0.021532772 -0.378038764 -0.164638087 0.053289842 -0.045927376 0.049807597 0.996278107
1403638130845096960 -0.035213359 -0.399767697 -0.168815717 0.053838573 -0.047568526 0.051275637 0.996097088
1403638130895097088 -0.029563135 -0.403555185 -0.183200508 0.055833258 -0.050043453 0.053412277 0.995753706
1403638130945096960 -0.033384692 -0.404285342 -0.175686762 0.062500529 -0.047989231 0.055246383 0.995358467
1403638130995097088 -0.033605658 -0.403358489 -0.178179443 0.072960302 -0.044466000 0.057964556 0.994655550
1403638131045096960 -0.019940805 -0.421546429 -0.181910485 0.080080450 -0.042631317 0.061666418 0.993965268
1403638131095097088 -0.021975648 -0.416398764 -0.188114315 0.082630172 -0.040316328 0.060403880 0.993930697
1403638131145096960 -0.020838559 -0.407805830 -0.184590340 0.078836381 -0.039460998 0.056481894 0.994503617
1403638131195097088 -0.017631017 -0.395692080 -0.178275704 0.070182450 -0.038760360 0.047742840 0.995636821
1403638131245096960 -0.019380223 -0.373631299 -0.169799566 0.060487792 -0.037363648 0.037063062 0.996780574
1403638131295097088 -0.015224226 -0.366670668 -0.158423305 0.052570216 -0.037577089 0.029129094 0.997484744
1403638131345096960 -0.020878121 -0.342549920 -0.146538928 0.049300741 -0.036940854 0.025831554 0.997766256
1403638131395097088 -0.023553392 -0.334133565 -0.138521001 0.048833475 -0.035529610 0.026309809 0.997828007
1403638131445096960 -0.020279374 -0.320057929 -0.140587702 0.049821135 -0.034646470 0.027168041 0.997787237
1403638131495097088 -0.017620185 -0.304195493 -0.140849337 0.049249139 -0.031294350 0.022395786 0.998044908
1403638131545096960 -0.013923215 -0.289176404 -0.127686992 0.046336748 -0.030784283 0.020656910 0.998237729
1403638131595097088 -0.018576197 -0.264691442 -0.128200546 0.043096256 -0.030166110 0.019629186 0.998422444
1403638131645096960 -0.009356648 -0.250473857 -0.119398549 0.040562909 -0.030732693 0.016996220 0.998559594
1403638131695097088 -0.001073002 -0.236694485 -0.116594873 0.040322468 -0.030301271 0.014831743 0.998616993
1403638131745096960 -0.004207710 -0.206622720 -0.103420883 0.040739190 -0.029041521 0.012443092 0.998670161
1403638131795097088 -0.004342438 -0.182179525 -0.091443703 0.040554628 -0.026225319 0.006768026 0.998810172
1403638131845096960 -0.000230730 -0.161978781 -0.089837685 0.038702730 -0.023266859 0.001568964 0.998978615
1403638131895097088 -0.001257707 -0.140112281 -0.080330223 0.038036406 -0.020749187 -0.000930385 0.999060452
1403638131945096960 0.008480201 -0.141795635 -0.071363948 0.036325369 -0.020152038 -0.003919845 0.999129117
1403638131995097088 0.009925192 -0.126273081 -0.065551102 0.033750784 -0.019501265 -0.009789959 0.999192059
1403638132045096960 0.010921103 -0.115312219 -0.064465359 0.029360745 -0.020177390 -0.019470016 0.999175549
1403638132095097088 0.010357000 -0.111643381 -0.061918121 0.023650957 -0.020781718 -0.028821407 0.999088645
1403638132145096960 0.009504993 -0.114575550 -0.062670119 0.020599784 -0.022238249 -0.034737121 0.998936653
1403638132195097088 0.009350434 -0.125302151 -0.067409702 0.022118090 -0.023999443 -0.034525715 0.998870730
1403638132245096960 0.009631768 -0.140608594 -0.076211482 0.028401097 -0.026816150 -0.028679714 0.998825192
1403638132295097088 0.008049581 -0.163599327 -0.087503523 0.036211211 -0.030383281 -0.021069294 0.998659968
1403638132345096960 -0.000821825 -0.170895070 -0.098617919 0.042843223 -0.031734187 -0.016498813 0.998441339
1403638132395097088 0.004643145 -0.217798784 -0.108989708 0.044171281 -0.037845284 -0.008574666 0.998270094
1403638132445096960 0.008277777 -0.245336950 -0.127273262 0.049117457 -0.042991728 -0.000812555 0.997866988
1403638132495097088 0.003875067 -0.268106908 -0.134252563 0.058299128 -0.048066646 0.011350415 0.997076690
1403638132545096960 -0.001942012 -0.284010768 -0.144273192 0.070645072 -0.051698580 0.023714133 0.995878577
1403638132595097088 -0.004554141 -0.308440208 -0.152694032 0.081250027 -0.054850765 0.033800066 0.994609118
1403638132645096960 -0.004610858 -0.328066677 -0.164960474 0.085241877 -0.057523988 0.039369505 0.993918955
1403638132695097088 -0.012781028 -0.345197737 -0.175131410 0.080527499 -0.058519930 0.040453117 0.994210362
1403638132745096960 -0.018450059 -0.355920792 -0.175191492 0.074205831 -0.059812717 0.040816646 0.994610429
1403638132795097088 -0.023684943 -0.369329005 -0.180702418 0.071575902 -0.059392948 0.042841971 0.994743168
1403638132845096960 -0.023784604 -0.369907707 -0.181439757 0.076143332 -0.060071070 0.046558015 0.994196177
1403638132895097088 -0.031281833 -0.369120657 -0.184147701 0.083854631 -0.059774600 0.053549331 0.993241131
1403638132945096960 -0.034288924 -0.374930114 -0.180937409 0.090131238 -0.061523918 0.057262722 0.992377043
1403638132995097088 -0.032055508 -0.374348164 -0.188301384 0.093134813 -0.064744741 0.056817383 0.991920292
1403638133045096960 -0.030091491 -0.357216984 -0.180714160 0.091767773 -0.065900728 0.049994413 0.992338836
1403638133095097088 -0.025857188 -0.351178288 -0.177467912 0.086724550 -0.064611964 0.040195160 0.993321955
1403638133145096960 -0.011862125 -0.342133641 -0.175745696 0.082217015 -0.062905490 0.035241328 0.994002700
1403638133195097088 -0.003015910 -0.332685769 -0.164347634 0.080447525 -0.056360945 0.032311704 0.994639456
1403638133245096960 0.009290473 -0.329233974 -0.163857967 0.079596460 -0.048716567 0.032941639 0.995090961
1403638133295097088 0.024841715 -0.325621992 -0.157343552 0.078003891 -0.037917588 0.032023322 0.995716929
1403638133345096960 0.054418337 -0.312300473 -0.158158004 0.073381126 -0.029110251 0.030404765 0.996415257
1403638133395097088 0.058897346 -0.297228873 -0.143067122 0.068635896 -0.019177778 0.027893137 0.997067332
1403638133445096960 0.086237796 -0.284990072 -0.147406548 0.064583533 -0.007327938 0.026065085 0.997544885
1403638133495097088 0.097625561 -0.281595677 -0.136901021 0.062850349 0.005170560 0.029000718 0.997588098
1403638133545096960 0.124658711 -0.267795652 -0.135683894 0.062160056 0.016310785 0.035165530 0.997313082
1403638133595097088 0.142190441 -0.257150233 -0.135817766 0.058980249 0.024076222 0.043371625 0.997025847
1403638133645096960 0.162465364 -0.240011513 -0.132960394 0.055483259 0.028989227 0.051480230 0.996710122
1403638133695097088 0.179114610 -0.226241425 -0.126272812 0.051965214 0.035153147 0.057874665 0.996350527
1403638133745096960 0.190702260 -0.226894587 -0.138297454 0.047928035 0.044607941 0.060336206 0.996028364
1403638133795097088 0.210946098 -0.219871059 -0.134763196 0.045992784 0.054622736 0.061234418 0.995565832
1403638133845096960 0.238364428 -0.197100431 -0.124917246 0.043945491 0.064193539 0.059248209 0.995207310
1403638133895097088 0.250132501 -0.187474787 -0.124158666 0.041178003 0.071782909 0.058813542 0.994832933
1403638133945096960 0.259461075 -0.184968680 -0.123831078 0.040376898 0.077371076 0.059832282 0.994386017
1403638133995097088 0.264136404 -0.185464069 -0.125564635 0.041185673 0.080283329 0.060213618 0.994098902
1403638134045096960 0.262552887 -0.188183427 -0.116090715 0.040449630 0.080287531 0.058287598 0.994243562
1403638134095097088 0.254580438 -0.189759642 -0.104975052 0.036666486 0.079087757 0.053651012 0.994747341
1403638134145096960 0.244538620 -0.194625378 -0.092470303 0.033593435 0.077783488 0.048621219 0.995217144
1403638134195097088 0.229790539 -0.197783142 -0.077034697 0.035386436 0.078209691 0.046264153 0.995234013
1403638134245096960 0.222535685 -0.202989861 -0.067328513 0.044170741 0.078380100 0.051254824 0.994624794
1403638134295097088 0.202440575 -0.215792149 -0.050258379 0.050502509 0.079039425 0.055977620 0.994016469
1403638134345096960 0.186187595 -0.224307284 -0.041338656 0.050525919 0.077196538 0.059986588 0.993926287
1403638134395097088 0.162757695 -0.234295622 -0.016758021 0.047859147 0.074521974 0.064812966 0.993959367
1403638134445096960 0.146430016 -0.243169785 -0.001526251 0.045066133 0.072263129 0.068150297 0.994033515
1403638134495097088 0.125789002 -0.251817405 0.005911358 0.045455813 0.070221409 0.071744248 0.993909240
1403638134545096960 0.107499979 -0.256965607 0.023671132 0.046654027 0.068373606 0.077376276 0.993559957
1403638134595097088 0.090522543 -0.261153996 0.031575024 0.048256792 0.064261071 0.082157649 0.993374050
1403638134645096960 0.067770302 -0.272103488 0.037575267 0.045935504 0.061864413 0.084093466 0.993474245
1403638134695097088 0.040995799 -0.271520644 0.053324036 0.042595722 0.059971463 0.083616026 0.993779361
1403638134745096960 0.013073582 -0.283401221 0.047695130 0.036528654 0.057155836 0.083086625 0.994231105
1403638134795097088 -0.012030312 -0.282495439 0.057006113 0.030684078 0.055506136 0.080476210 0.994736731
1403638134845096960 -0.030572565 -0.291585922 0.057905585 0.027163344 0.055039860 0.077615082 0.995092273
1403638134895097088 -0.048949130 -0.297295690 0.058282889 0.027596502 0.055395711 0.075780705 0.995202005
1403638134945096960 -0.068706132 -0.302429378 0.054342549 0.031499371 0.055728734 0.075402804 0.995096207
1403638134995097088 -0.088246748 -0.309318691 0.060611811 0.034314785 0.056055512 0.076449096 0.994904935
1403638135045096960 -0.101649143 -0.309071749 0.062791795 0.032834530 0.055870701 0.072690293 0.995246947
1403638135095097088 -0.108956628 -0.309774876 0.059408825 0.028471921 0.054404922 0.068317033 0.995772183
1403638135145096960 -0.126501426 -0.304780334 0.063638180 0.024921205 0.053047799 0.064030260 0.996225357
1403638135195097088 -0.136961192 -0.300308138 0.068528421 0.021980561 0.052670255 0.060764059 0.996519148
1403638135245096960 -0.136193126 -0.298003972 0.061316699 0.018621160 0.052095156 0.058966469 0.996725798
1403638135295097088 -0.139121175 -0.290257066 0.065234579 0.019183718 0.053540237 0.057097059 0.996747375
1403638135345096960 -0.138059527 -0.283630580 0.063290171 0.021790635 0.055178057 0.057148937 0.996601462
1403638135395097088 -0.131074190 -0.273431957 0.065687142 0.023754008 0.058037277 0.057057049 0.996399462
1403638135445096960 -0.122625202 -0.270029753 0.057523921 0.022024261 0.062354218 0.054153506 0.996340454
1403638135495097088 -0.091597036 -0.251576155 0.054967191 0.019787770 0.063744523 0.051413141 0.996444583
1403638135545096960 -0.089133993 -0.254278630 0.050412510 0.014161473 0.067170098 0.050662275 0.996353805
1403638135595097088 -0.077781953 -0.250085175 0.049648650 0.010583275 0.071991928 0.047301657 0.996226728
1403638135645096960 -0.073182419 -0.249916121 0.049826570 0.012048865 0.077673070 0.046981424 0.995798409
1403638135695097088 -0.052177645 -0.240384594 0.043666884 0.016866470 0.082654819 0.052135229 0.995070636
1403638135745096960 -0.020472715 -0.238901660 0.025608677 0.021130009 0.084996201 0.060108054 0.994342089
1403638135795097088 0.001257346 -0.225160301 0.026883468 0.021512998 0.086002104 0.065000683 0.993939519
1403638135845096960 0.021400230 -0.230825439 0.008361893 0.018105170 0.088571988 0.063125350 0.993902624
1403638135895097088 0.026071174 -0.219085559 0.004215650 0.011964742 0.092659488 0.055625867 0.994070828
1403638135945096960 0.038622044 -0.218237549 -0.009320521 0.004532475 0.095687151 0.049390394 0.994175017
1403638135995097088 0.070708573 -0.230255291 -0.027049169 0.000818496 0.099456966 0.045758702 0.993988812
1403638136045096960 0.082659237 -0.228932187 -0.037927657 0.004361140 0.105482586 0.043525126 0.993458569
1403638136095097088 0.103368729 -0.241005465 -0.055112474 0.012152025 0.110901371 0.045614749 0.992709696
1403638136145096960 0.125059441 -0.244580567 -0.064163372 0.020733226 0.114555523 0.051959056 0.991840422
1403638136195097088 0.140284419 -0.233177260 -0.076549947 0.029664267 0.117068030 0.058327485 0.990965664
1403638136245096960 0.165132925 -0.240990922 -0.084104456 0.031210462 0.120197795 0.061223123 0.990368664
1403638136295097088 0.178025082 -0.221669585 -0.094764374 0.032708321 0.125731111 0.059346851 0.989747345
1403638136345096960 0.193517044 -0.211368442 -0.103081122 0.031113643 0.131262794 0.056482464 0.989248037
1403638136395097088 0.205002084 -0.204687625 -0.110255718 0.028392479 0.134482577 0.054881584 0.988987505
1403638136445096960 0.216720805 -0.195171162 -0.112392060 0.025389826 0.137944266 0.052393749 0.988727272
1403638136495097088 0.232535943 -0.186950296 -0.116107933 0.023484705 0.140069366 0.054032594 0.988387346
1403638136545096960 0.231102377 -0.192332745 -0.120267674 0.020712467 0.142167643 0.059450157 0.987838626
1403638136595097088 0.231365651 -0.193772778 -0.123883963 0.021242326 0.141405389 0.065729879 0.987538815
1403638136645096960 0.222875446 -0.198139742 -0.125917792 0.023446424 0.137178600 0.070870087 0.987729609
1403638136695097088 0.223458260 -0.200426042 -0.131350160 0.025226440 0.130569935 0.075465813 0.988240898
1403638136745096960 0.207351685 -0.226270750 -0.134235710 0.024463646 0.124224611 0.077186555 0.988944888
1403638136795097088 0.197916061 -0.215179190 -0.120818987 0.028559109 0.114366047 0.081305787 0.989693999
1403638136845096960 0.163476348 -0.240033418 -0.129628241 0.032823950 0.105514489 0.086738102 0.990083694
1403638136895097088 0.146517828 -0.259901315 -0.127736807 0.040483594 0.096010111 0.095676556 0.989943981
1403638136945096960 0.126405150 -0.243870690 -0.122716278 0.051692825 0.087883323 0.103547521 0.989384830
1403638136995097088 0.111946613 -0.253297210 -0.122023717 0.058148690 0.081806801 0.108888097 0.988974094
1403638137045096960 0.084835567 -0.237049848 -0.111199811 0.061253116 0.076276764 0.110617392 0.989036798
1403638137095097088 0.066299602 -0.225634366 -0.099182665 0.059099194 0.073150374 0.107635915 0.989732742
1403638137145096960 0.052420449 -0.238872677 -0.089644641 0.052555561 0.071487904 0.101573162 0.990863383
1403638137195097088 0.042106956 -0.216430008 -0.079131164 0.045849249 0.068130970 0.094974875 0.992086589
1403638137245096960 0.025052439 -0.195470020 -0.062744461 0.038127497 0.065841980 0.087147728 0.993285656
1403638137295097088 0.013782192 -0.178358510 -0.064311162 0.032517537 0.063257940 0.081261583 0.994151652
1403638137345096960 0.004381857 -0.161257550 -0.057154015 0.027936481 0.060761295 0.078151032 0.994695961
1403638137395097088 -0.007085091 -0.140773773 -0.050195474 0.023790855 0.061374076 0.073640719 0.995110154
1403638137445096960 -0.014199850 -0.124309801 -0.042425517 0.017538298 0.062787168 0.068433061 0.995523512
1403638137495097088 -0.021042405 -0.106770232 -0.034695067 0.010168300 0.064901568 0.061290223 0.995955765
1403638137545096960 -0.025825936 -0.089465976 -0.026698103 0.001835548 0.067230202 0.053088501 0.996322393
1403638137595097088 -0.029481528 -0.073796548 -0.019960541 -0.004838374 0.071035542 0.044012196 0.996490598
1403638137645096960 -0.032593358 -0.061584283 -0.013982942 -0.007296143 0.073805191 0.040340021 0.996429741
1403638137695097088 -0.034870043 -0.051482040 -0.009299962 -0.006649600 0.077878684 0.039428350 0.996160626
1403638137745096960 -0.035990600 -0.042778343 -0.005607599 -0.004822230 0.081285149 0.040297162 0.995864213
1403638137795097088 -0.034738064 -0.038478021 0.005399537 -0.005018986 0.083622277 0.041229919 0.995631576
1403638137845096960 -0.035795398 -0.030682115 0.008081262 -0.008558643 0.085384667 0.039458241 0.995529652
1403638137895097088 -0.039965671 -0.020164942 0.001091341 -0.016654713 0.086269051 0.036147863 0.995476544
1403638137945096960 -0.038718328 -0.017096804 0.009622088 -0.024344454 0.087799549 0.031463679 0.995343447
1403638137995097088 -0.042134434 -0.008715415 0.003304147 -0.032973975 0.086920753 0.026273346 0.995322645
1403638138045096960 -0.040396854 -0.009249725 0.012220656 -0.035080664 0.087235406 0.021060990 0.995347083
1403638138095097088 -0.041276008 -0.007331032 0.012420541 -0.033230219 0.086939655 0.020981196 0.995438159
1403638138145096960 -0.040238336 -0.007978219 0.013574979 -0.024485268 0.087995313 0.025103623 0.995503485
1403638138195097088 -0.039926760 -0.007475215 0.013762657 -0.018628445 0.088748492 0.029136574 0.995453537
1403638138245096960 -0.040185992 -0.006088872 0.013754732 -0.015162180 0.088898025 0.031503383 0.995426953
1403638138295097088 -0.039667796 -0.006094432 0.015179767 -0.011603374 0.089694768 0.031439792 0.995405316
1403638138345096960 -0.040096313 -0.006080666 0.014337681 -0.008173442 0.090179063 0.031278856 0.995400667
1403638138395097088 -0.040191062 -0.005955417 0.013743879 -0.003476186 0.090378769 0.031840675 0.995392263
1403638138445096960 -0.040496372 -0.005738518 0.012960553 -0.003187842 0.090716727 0.030679228 0.995398939
1403638138495097088 -0.040466934 -0.005605081 0.013115400 -0.003022420 0.091014758 0.029717367 0.995401442
1403638138545096960 -0.040443987 -0.005438583 0.013243774 -0.002021459 0.091111019 0.032802615 0.995298266
1403638138595097088 -0.040569156 -0.005573951 0.013041545 -0.003022445 0.091211513 0.029635601 0.995385826
1403638138645096960 -0.040441543 -0.005639278 0.013473718 -0.002919735 0.090880334 0.030824378 0.995380342
1403638138695097088 -0.040398885 -0.005500580 0.013403548 -0.002019876 0.090646908 0.034081843 0.995297670
1403638138745096960 -0.040532757 -0.005504236 0.013307691 -0.002061866 0.090751126 0.033195302 0.995318055
1403638138795097088 -0.040518943 -0.005353025 0.013077160 -0.002189322 0.090397753 0.033114117 0.995352626
1403638138845096960 -0.040651660 -0.005602346 0.013517754 -0.003066433 0.090751804 0.029814178 0.995422423
1403638138895097088 -0.040936340 -0.005615390 0.013387538 -0.001403867 0.089665003 0.035637829 0.995333195
1403638138945096960 -0.040444978 -0.005336758 0.013305696 -0.002163510 0.090226710 0.033504624 0.995355189
1403638138995097088 -0.040684212 -0.005595362 0.013299050 -0.001798147 0.089801200 0.035447083 0.995327055
1403638139045096960 -0.040449776 -0.005401862 0.013311382 -0.001716458 0.089889668 0.034337871 0.995358109
1403638139095097088 -0.040610030 -0.005509022 0.013244843 -0.001917407 0.089909695 0.034756664 0.995341420
1403638139145096960 -0.040732924 -0.005620108 0.013176672 -0.001855724 0.089884676 0.035127785 0.995330751
1403638139195097088 -0.040470861 -0.005416190 0.013300334 -0.001954845 0.090218410 0.034412909 0.995325327
1403638139245096960 -0.040683601 -0.005496928 0.013255972 -0.001679537 0.089745253 0.035496693 0.995330572
1403638139295097088 -0.040364627 -0.005439053 0.013470281 -0.001883328 0.090061881 0.034042064 0.995352387
1403638139345096960 -0.040547632 -0.005403833 0.013245374 -0.001773231 0.089619122 0.034964059 0.995360613
1403638139395097088 -0.040435590 -0.005350515 0.013341621 -0.001805327 0.089887835 0.034416895 0.995355427
1403638139445096960 -0.040495615 -0.005433880 0.013422651 -0.001775192 0.089999966 0.034756761 0.995333493
1403638139495097088 -0.040510993 -0.005503261 0.013138197 -0.001911289 0.089795873 0.034819506 0.995349526
1403638139545096960 -0.040598780 -0.005491545 0.013140472 -0.001960467 0.089912549 0.034838762 0.995338202
1403638139595097088 -0.040654492 -0.005660991 0.013196565 -0.001890688 0.090082653 0.034357302 0.995339692
1403638139645096960 -0.040639158 -0.005647467 0.013282629 -0.001918100 0.090278052 0.034273595 0.995324850
1403638139695097088 -0.040694281 -0.005693811 0.013193387 -0.001985750 0.090099312 0.034436956 0.995335221
1403638139745096960 -0.040690523 -0.005699356 0.013258579 -0.002045278 0.090282403 0.034203336 0.995326579
1403638139795097088 -0.040702216 -0.005620198 0.013280750 -0.001821763 0.090102963 0.034631222 0.995328486
1403638139845096960 -0.040616956 -0.005637340 0.013209021 -0.001896857 0.090153277 0.034282137 0.995335877
1403638139895097088 -0.040627681 -0.005360377 0.013209807 -0.001602821 0.089928679 0.034818448 0.995338082
1403638139945096960 -0.040626928 -0.005516289 0.013177717 -0.001901154 0.090000726 0.034821231 0.995330989
1403638139995097088 -0.040694356 -0.005252041 0.013519886 -0.001469678 0.090161026 0.034282055 0.995335877
1403638140045096960 -0.040637802 -0.005388414 0.013523059 -0.001624721 0.090055317 0.034468900 0.995338738
1403638140095097088 -0.040611625 -0.005332630 0.013481861 -0.001566435 0.090094976 0.034559187 0.995332181
1403638140145096960 -0.040767461 -0.005347832 0.013556791 -0.001641893 0.090341158 0.034271579 0.995319664
1403638140195097088 -0.040637057 -0.005332320 0.013497710 -0.001511255 0.090107404 0.034568675 0.995330811
1403638140245096960 -0.040618233 -0.005394135 0.013398651 -0.001625677 0.090015769 0.034602601 0.995337725
1403638140295097088 -0.040742345 -0.005503743 0.013011925 -0.001753046 0.090005651 0.034832899 0.995330393
1403638140345096960 -0.040659718 -0.005428195 0.013050022 -0.001646113 0.089877449 0.034761261 0.995344639
1403638140395097088 -0.040702078 -0.005468167 0.013245774 -0.001897862 0.090018205 0.034659844 0.995335042
1403638140445096960 -0.040630348 -0.005473888 0.013048517 -0.001697695 0.089906193 0.034705695 0.995343924
1403638140495097088 -0.040612806 -0.005535152 0.013136356 -0.001962680 0.089895204 0.034879137 0.995338380
1403638140545096960 -0.040672787 -0.005537362 0.013111657 -0.001801877 0.089960046 0.034933254 0.995330870
1403638140595097088 -0.040636212 -0.005424911 0.013081584 -0.001646820 0.089900360 0.034869451 0.995338798
1403638140645096960 -0.040636849 -0.005511033 0.013135381 -0.001836411 0.089880005 0.034800325 0.995342731
1403638140695097088 -0.040590517 -0.005437917 0.013105882 -0.001653960 0.089954093 0.034979202 0.995330095
1403638140745096960 -0.040631700 -0.005424323 0.013168278 -0.001694094 0.090003394 0.034783468 0.995332420
1403638140795097088 -0.040662959 -0.005375450 0.013192321 -0.001604739 0.089945093 0.034702059 0.995340705
1403638140845096960 -0.040615086 -0.005424822 0.013220295 -0.001676938 0.089966625 0.034845863 0.995333552
1403638140895097088 -0.040514752 -0.005366710 0.013307860 -0.001626781 0.089875534 0.035022959 0.995335698
1403638140945096960 -0.040569928 -0.005486095 0.013216132 -0.001734738 0.089871004 0.035069346 0.995334268
1403638140995097088 -0.040592127 -0.005418562 0.013195505 -0.001632561 0.089960627 0.035017639 0.995328128
1403638141045096960 -0.040539317 -0.005457851 0.013225896 -0.001692278 0.089839794 0.035156634 0.995334029
1403638141095097088 -0.040560026 -0.005452916 0.013291360 -0.001674175 0.089843445 0.034979217 0.995340049
1403638141145096960 -0.040580034 -0.005455365 0.013409108 -0.001720021 0.090070926 0.034832031 0.995324552
1403638141195097088 -0.040542178 -0.005390614 0.013239877 -0.001619865 0.089909762 0.035009254 0.995333076
1403638141245096960 -0.040536679 -0.005386956 0.013258392 -0.001681390 0.089919060 0.035049438 0.995330691
1403638141295097088 -0.040661406 -0.005481805 0.013174213 -0.001873531 0.089971371 0.034571894 0.995342374
1403638141345096960 -0.040558923 -0.005475638 0.013173293 -0.001795160 0.089900278 0.034942795 0.995335996
1403638141395097088 -0.040588472 -0.005466930 0.013192665 -0.001744977 0.090021677 0.034808043 0.995329797
1403638141445096960 -0.040598691 -0.005410513 0.013214745 -0.001678959 0.089953758 0.034821466 0.995335579
1403638141495097088 -0.040672608 -0.005506133 0.013158825 -0.001744116 0.090004712 0.035006568 0.995324373
1403638141545096960 -0.040517565 -0.005417841 0.013204077 -0.001670964 0.089853667 0.034978531 0.995339155
1403638141595097088 -0.040623903 -0.005477107 0.013069075 -0.001754881 0.089907154 0.035103213 0.995329797
1403638141645096960 -0.040501229 -0.005445555 0.013227070 -0.001721615 0.089823730 0.035123710 0.995336652
1403638141695097088 -0.040610366 -0.005512878 0.013311038 -0.001862000 0.090016551 0.034834113 0.995329142
1403638141745096960 -0.040491305 -0.005373002 0.013232996 -0.001583703 0.089759767 0.035179168 0.995340705
1403638141795097088 -0.040606912 -0.005421651 0.013256645 -0.001717436 0.089967422 0.034977686 0.995328844
1403638141845096960 -0.040596213 -0.005406043 0.013158347 -0.001835608 0.089933254 0.034710359 0.995341063
1403638141895097088 -0.040647551 -0.005418594 0.013319746 -0.001732919 0.090075240 0.034794733 0.995325446
1403638141945096960 -0.040569037 -0.005378666 0.013225794 -0.001605585 0.090034246 0.035150833 0.995316863
1403638141995097088 -0.040627789 -0.005555862 0.013238302 -0.001994202 0.089853935 0.034866083 0.995342493
1403638142045096960 -0.040575262 -0.005499292 0.013271382 -0.001910731 0.089782074 0.034872595 0.995348930
1403638142095097088 -0.040674739 -0.005467218 0.013173753 -0.001828818 0.089894019 0.034730114 0.995343924
1403638142145096960 -0.040611885 -0.005468586 0.013204677 -0.001787432 0.089714073 0.035151307 0.995345473
1403638142195097088 -0.040595416 -0.005490225 0.013319573 -0.001885054 0.090164170 0.034912150 0.995312989
1403638142245096960 -0.040410601 -0.005460648 0.013499578 -0.002048317 0.090420611 0.034730885 0.995295763
1403638142295097088 -0.040411200 -0.005477865 0.013506033 -0.001956486 0.090608701 0.034718551 0.995279253
1403638142345096960 -0.040407915 -0.005448375 0.013359741 -0.001912964 0.090323813 0.034746166 0.995304286
1403638142395097088 -0.040480867 -0.005424412 0.013403455 -0.001893137 0.090472713 0.034425218 0.995301962
1403638142445096960 -0.040407211 -0.005473163 0.013366174 -0.001999286 0.090019807 0.034866933 0.995327413
1403638142495097088 -0.040448945 -0.005473725 0.013313456 -0.001947413 0.089937143 0.034883454 0.995334446
1403638142545096960 -0.040592413 -0.005503330 0.013322911 -0.001956198 0.089955479 0.035111088 0.995324790
1403638142595097088 -0.040572476 -0.005476212 0.013186295 -0.001828788 0.089268290 0.035141546 0.995385766
1403638142645096960 -0.040524092 -0.005463676 0.013269087 -0.001843238 0.089400597 0.035002250 0.995378792
1403638142695097088 -0.040538233 -0.005411797 0.013386223 -0.001787331 0.089433767 0.034930326 0.995378435
1403638142745096960 -0.040703107 -0.005552474 0.013237150 -0.001999634 0.089672156 0.034879379 0.995358407
1403638142795097088 -0.040602412 -0.005474071 0.013443672 -0.001888539 0.090225585 0.034917250 0.995307267
1403638142845096960 -0.040614855 -0.005507062 0.013420528 -0.001919057 0.090081342 0.034913484 0.995320380
1403638142895097088 -0.040596843 -0.005424413 0.013245156 -0.001725759 0.090065047 0.034688696 0.995330095
1403638142945096960 -0.040598683 -0.005424933 0.013341274 -0.001698417 0.089742959 0.034816116 0.995354772
1403638142995097088 -0.040671013 -0.005528240 0.013365244 -0.001941591 0.089693896 0.034710586 0.995362461
1403638143045096960 -0.040651973 -0.005477017 0.013233172 -0.001843149 0.089603439 0.034626152 0.995373726
1403638143095097088 -0.040585253 -0.005488196 0.013327232 -0.001914191 0.089717485 0.034537528 0.995366395
1403638143145096960 -0.040654160 -0.005462460 0.013306079 -0.001899316 0.089882217 0.034496620 0.995352983
1403638143195097088 -0.040575378 -0.005463032 0.013443269 -0.001891097 0.089894257 0.034689792 0.995345175
1403638143245096960 -0.040705621 -0.005454917 0.013237254 -0.001867571 0.089872770 0.034534704 0.995352566
1403638143295097088 -0.040608935 -0.005438897 0.013167897 -0.001857550 0.089823708 0.034670752 0.995352268
1403638143345096960 -0.040612988 -0.005458876 0.013277937 -0.001921881 0.089884713 0.034467328 0.995353699
1403638143395097088 -0.040500797 -0.005406597 0.013199680 -0.001826977 0.089676060 0.034782741 0.995361745
1403638143445096960 -0.040518239 -0.005454758 0.013225420 -0.001930563 0.089784101 0.034705225 0.995354533
1403638143495097088 -0.040718589 -0.005500177 0.013241034 -0.001924583 0.090036385 0.034743357 0.995330393
1403638143545096960 -0.040644728 -0.005422121 0.013204376 -0.001729518 0.089934088 0.034755412 0.995339572
1403638143595097088 -0.040527407 -0.005393028 0.013310555 -0.001686345 0.090183802 0.035022348 0.995307744
1403638143645096960 -0.040610366 -0.005472529 0.013174872 -0.001870809 0.089941241 0.034834150 0.995335937
1403638143695097088 -0.040508460 -0.005428804 0.013253404 -0.001789129 0.089873619 0.034963917 0.995337665
1403638143745096960 -0.040411826 -0.005485339 0.013290334 -0.001825329 0.089758031 0.035130680 0.995342135
1403638143795097088 -0.040656965 -0.005428543 0.013200292 -0.001721328 0.089966230 0.034851756 0.995333314
1403638143845096960 -0.040520281 -0.005485468 0.013238812 -0.001814503 0.089773387 0.034931038 0.995347798
1403638143895097088 -0.040517177 -0.005410027 0.013216930 -0.001700181 0.089751221 0.034921270 0.995350361
1403638143945096960 -0.040448964 -0.005456800 0.013313809 -0.001781076 0.089841865 0.034964483 0.995340526
1403638143995097088 -0.040533260 -0.005380858 0.013231639 -0.001710251 0.089881696 0.034832772 0.995341659
1403638144045096960 -0.040531427 -0.005463547 0.013330186 -0.001867448 0.089888446 0.034852881 0.995340049
1403638144095097088 -0.040457021 -0.005444285 0.013383629 -0.001797400 0.089953102 0.035069089 0.995326817
1403638144145096960 -0.040509652 -0.005398929 0.013319427 -0.001775043 0.089891702 0.034808222 0.995341539
1403638144195097088 -0.040582929 -0.005483759 0.013266657 -0.001792727 0.089946695 0.034980852 0.995330453
1403638144245096960 -0.040556461 -0.005491336 0.013360087 -0.001891443 0.089932591 0.034883302 0.995334983
1403638144295097088 -0.040478826 -0.005492529 0.013226239 -0.001800151 0.089734294 0.035134193 0.995344222
1403638144345096960 -0.040498644 -0.005482410 0.013283613 -0.001962356 0.089880042 0.034795538 0.995342672
1403638144395097088 -0.040599957 -0.005493841 0.013273590 -0.001887464 0.089913867 0.034931879 0.995334983
1403638144445096960 -0.040540498 -0.005533948 0.013287241 -0.001879394 0.089919604 0.034888897 0.995335996
1403638144495097088 -0.040518969 -0.005496768 0.013312036 -0.001932757 0.089996688 0.034830350 0.995330989
1403638144545096960 -0.040520579 -0.005530797 0.013326128 -0.001947893 0.089936361 0.034806389 0.995337248
1403638144595097088 -0.040594291 -0.005493146 0.013262544 -0.001851903 0.089957014 0.034892417 0.995332539
1403638144645096960 -0.040642157 -0.005481272 0.013184464 -0.001955138 0.089932367 0.034704361 0.995341122
1403638144695097088 -0.040591102 -0.005499214 0.013268564 -0.001814769 0.089895442 0.034767546 0.995342553
1403638144745096960 -0.040562708 -0.005494617 0.013269888 -0.001945887 0.089855999 0.034812156 0.995344281
1403638144795097088 -0.040601112 -0.005537989 0.013208626 -0.001903441 0.089904308 0.035002578 0.995333314
1403638144845096960 -0.040556628 -0.005516323 0.013186518 -0.001873913 0.089895211 0.034891352 0.995338082
1403638144895097088 -0.040499102 -0.005508523 0.013248954 -0.001843965 0.089802667 0.034962952 0.995343983
1403638144945096960 -0.040593993 -0.005497354 0.013218183 -0.001856128 0.089931063 0.035065290 0.995328784
1403638144995097088 -0.040543836 -0.005506705 0.013199997 -0.001876073 0.089858614 0.034900498 0.995341122
1403638145045096960 -0.040522549 -0.005488850 0.013236976 -0.001929570 0.089842103 0.034857523 0.995343983
1403638145095097088 -0.040474225 -0.005446683 0.013334827 -0.001787091 0.089800783 0.034982231 0.995343626
1403638145145096960 -0.040517643 -0.005416334 0.013303995 -0.001857489 0.089892447 0.034897152 0.995338202
1403638145195097088 -0.040505841 -0.005514471 0.013299648 -0.001894027 0.089856513 0.034950398 0.995339513
1403638145245096960 -0.040528975 -0.005441691 0.013211193 -0.001858790 0.089868307 0.034819528 0.995343089
1403638145295097088 -0.040494047 -0.005434019 0.013301838 -0.001773119 0.089812025 0.034962080 0.995343328
1403638145345096960 -0.040601190 -0.005517412 0.013170602 -0.001928439 0.089900255 0.034878671 0.995337963
1403638145395097088 -0.040551890 -0.005503204 0.013268271 -0.001938548 0.090027705 0.034806535 0.995328963
1403638145445096960 -0.040561471 -0.005505874 0.013222550 -0.001831130 0.090103090 0.034971554 0.995316565
1403638145495097088 -0.040492859 -0.005471921 0.013288306 -0.001851572 0.089843348 0.035006147 0.995338798
1403638145545096960 -0.040565614 -0.005585214 0.013307343 -0.001983210 0.090028666 0.034725882 0.995331645
1403638145595097088 -0.040581785 -0.005509474 0.013262419 -0.001891303 0.090050593 0.034834720 0.995325983
1403638145645096960 -0.040594466 -0.005570060 0.013252948 -0.001972320 0.090018235 0.034829136 0.995328963
1403638145695097088 -0.040522501 -0.005393360 0.013249865 -0.001665751 0.089905240 0.034704477 0.995344102
1403638145745096960 -0.040555842 -0.005386824 0.013328046 -0.001749883 0.089915276 0.035044115 0.995331168
1403638145795097088 -0.040527992 -0.005485472 0.013325112 -0.001926238 0.089962021 0.034763083 0.995336473
1403638145845096960 -0.040504914 -0.005442707 0.013332885 -0.001731057 0.089899316 0.034846112 0.995339572
1403638145895097088 -0.040591940 -0.005515426 0.013421574 -0.001974647 0.090015367 0.034654282 0.995335340
1403638145945096960 -0.040549252 -0.005509495 0.013302337 -0.001952882 0.089934684 0.034699466 0.995341122
1403638145995097088 -0.040558420 -0.005439013 0.013316678 -0.001747867 0.089951336 0.034884565 0.995333493
1403638146045096960 -0.040490802 -0.005528167 0.013232926 -0.001923759 0.089830361 0.034986254 0.995340526
1403638146095097088 -0.040600367 -0.005391936 0.013265084 -0.001746419 0.089932859 0.034628917 0.995344102
1403638146145096960 -0.040668242 -0.005440674 0.013292324 -0.001779287 0.090032019 0.034761697 0.995330453
1403638146195097088 -0.040641829 -0.005495156 0.013290399 -0.001815544 0.090018682 0.034815360 0.995329738
1403638146245096960 -0.040572949 -0.005458584 0.013335103 -0.001705902 0.089930646 0.035058890 0.995329320
1403638146295097088 -0.040588599 -0.005513681 0.013376178 -0.001804743 0.089968570 0.034695338 0.995338440
1403638146345096960 -0.040526778 -0.005517984 0.013438681 -0.001861437 0.089892559 0.034776211 0.995342433
1403638146395097088 -0.040523387 -0.005495579 0.013259484 -0.001759518 0.089804210 0.034735091 0.995351970
1403638146445096960 -0.040515259 -0.005501939 0.013442256 -0.001733958 0.089876220 0.034967352 0.995337427
1403638146495097088 -0.040658779 -0.005499197 0.013246549 -0.001789951 0.090025097 0.034696307 0.995333374
1403638146545096960 -0.040505953 -0.005452357 0.013248900 -0.001609853 0.089880452 0.034939237 0.995338261
1403638146595097088 -0.040507037 -0.005414143 0.013494852 -0.001639275 0.089892536 0.034846306 0.995340347
1403638146645096960 -0.040614188 -0.005389837 0.013465309 -0.001567197 0.090033084 0.034771774 0.995330393
1403638146695097088 -0.040634818 -0.005463466 0.013318887 -0.001604358 0.090047508 0.034740917 0.995330095
1403638146745096960 -0.040494792 -0.005460698 0.013437971 -0.001676582 0.089917928 0.034903634 0.995335996
1403638146795097088 -0.040429827 -0.005456400 0.013422953 -0.001615808 0.089757152 0.034954838 0.995348811
1403638146845096960 -0.040464640 -0.005468044 0.013447320 -0.001702687 0.089925110 0.034790397 0.995339274
1403638146895097088 -0.040514160 -0.005431372 0.013568657 -0.001488378 0.089863025 0.034746446 0.995346725
1403638146945096960 -0.040535334 -0.005454793 0.013459556 -0.001654170 0.089864954 0.034840703 0.995343029
1403638146995097088 -0.040546257 -0.005441789 0.013417521 -0.001643186 0.089830577 0.034531418 0.995356917
1403638147045096960 -0.040639028 -0.005480243 0.013429109 -0.001780161 0.089927331 0.034875903 0.995335937
1403638147095097088 -0.040739670 -0.005580198 0.013212914 -0.001919641 0.089816436 0.035065155 0.995339036
1403638147145096960 -0.040601883 -0.005501164 0.013573665 -0.002058896 0.089364670 0.035401348 0.995367527
1403638147195097088 -0.040610537 -0.005472969 0.013339679 -0.002078587 0.089575768 0.035280846 0.995352745
1403638147245096960 -0.040622253 -0.005526247 0.013461376 -0.002027831 0.089333855 0.035488848 0.995367229
1403638147295097088 -0.040815178 -0.005544407 0.013254082 -0.002022074 0.089668043 0.035338793 0.995342493
1403638147345096960 -0.040670253 -0.005530493 0.013350742 -0.001854635 0.089519054 0.035196796 0.995361328
1403638147395097088 -0.040682465 -0.005542527 0.013338830 -0.001848898 0.089488067 0.035373818 0.995357811
1403638147445096960 -0.040701933 -0.005597911 0.013440942 -0.001854214 0.089597680 0.035176005 0.995354950
1403638147495097088 -0.040520988 -0.005774661 0.013402032 -0.000887897 0.089394517 0.035213772 0.995373189
1403638147545096960 -0.040337536 -0.005691243 0.013622852 -0.000674971 0.089472733 0.035335671 0.995362043
1403638147595097088 -0.040618941 -0.005962186 0.013299124 0.000047910 0.089082748 0.035477009 0.995392203
1403638147645096960 -0.040402420 -0.005801725 0.013715951 -0.000550392 0.088920899 0.034592610 0.995437682
1403638147695097088 -0.040559396 -0.005911517 0.013944027 -0.000075281 0.088417418 0.035421547 0.995453477
1403638147745096960 -0.040502172 -0.006808711 0.014619302 0.000359453 0.088303812 0.034701571 0.995488882
1403638147795097088 -0.040019352 -0.008038910 0.016109008 0.003061719 0.089815557 0.033648942 0.995385110
1403638147845096960 -0.039160080 -0.010227917 0.017262245 0.007531944 0.091584384 0.034307003 0.995177686
1403638147895097088 -0.038087513 -0.014268493 0.019020708 0.015681002 0.093159035 0.035529740 0.994893551
1403638147945096960 -0.036887541 -0.020302000 0.021973429 0.022134235 0.094788589 0.036240619 0.994591296
1403638147995097088 -0.036407325 -0.028014515 0.023357764 0.027072638 0.095356509 0.036788940 0.994394660
1403638148045096960 -0.034787729 -0.037917696 0.025447844 0.031748615 0.096210480 0.035833132 0.994208992
1403638148095097088 -0.033950284 -0.049814083 0.028402878 0.035817411 0.096176587 0.035501357 0.994085908
1403638148145096960 -0.041678641 -0.042454209 0.019861560 0.038927726 0.095578589 0.034749232 0.994053245
1403638148195097088 -0.040820643 -0.061555989 0.018251710 0.040989317 0.094336376 0.033310492 0.994138300
1403638148245096960 -0.041286923 -0.082575470 0.012129080 0.041692510 0.092783175 0.033183254 0.994259477
1403638148295097088 -0.040792000 -0.105451152 0.009399524 0.041848343 0.091481104 0.032163188 0.994407058
1403638148345096960 -0.031820145 -0.145466715 0.005488699 0.042349428 0.089689575 0.031465016 0.994571388
1403638148395097088 -0.030160172 -0.169632167 0.004313525 0.042060960 0.088307120 0.030517317 0.994736850
1403638148445096960 -0.027938154 -0.189648882 0.000195335 0.040959489 0.087168694 0.029809473 0.994904697
1403638148495097088 -0.026825767 -0.206752419 -0.003658705 0.035863049 0.086349279 0.028419033 0.995213509
1403638148545096960 -0.026627062 -0.217117652 -0.006216187 0.032443553 0.085908651 0.026774902 0.995414615
1403638148595097088 -0.034821406 -0.209903285 -0.002369077 0.029837416 0.084970817 0.026215868 0.995591521
1403638148645096960 -0.026527166 -0.221952990 -0.000410871 0.025485344 0.083847426 0.025243595 0.995832741
1403638148695097088 -0.028631758 -0.222692087 0.006644310 0.022476690 0.082986414 0.024980187 0.995983958
1403638148745096960 -0.030305827 -0.220569268 0.018233109 0.020146394 0.081653818 0.025045723 0.996142268
1403638148795097088 -0.030256031 -0.221824884 0.023091856 0.018172685 0.080593161 0.025137700 0.996264338
1403638148845096960 -0.031107599 -0.226289541 0.031380702 0.017485037 0.079241633 0.025182432 0.996383846
1403638148895097088 -0.034725521 -0.233640015 0.041938338 0.017129669 0.078690305 0.024844332 0.996442199
1403638148945096960 -0.045011386 -0.231247500 0.043432843 0.019523770 0.077906728 0.024753774 0.996462047
1403638148995097088 -0.037416272 -0.258433044 0.051709957 0.020703841 0.076968119 0.024473844 0.996518075
1403638149045096960 -0.034822945 -0.275911391 0.053621225 0.024459183 0.076007977 0.023861654 0.996521473
1403638149095097088 -0.046044640 -0.285469145 0.064820066 0.028469078 0.076655842 0.023111288 0.996383071
1403638149145096960 -0.049790405 -0.307398379 0.064844131 0.031193659 0.075750671 0.022646457 0.996381402
1403638149195097088 -0.055499874 -0.331371725 0.069952294 0.032324068 0.076073930 0.022609133 0.996321619
1403638149245096960 -0.053098470 -0.347941607 0.075549893 0.034336824 0.075447425 0.023379078 0.996284127
1403638149295097088 -0.056384467 -0.373639852 0.074941121 0.034866445 0.074834801 0.024825143 0.996276975
1403638149345096960 -0.060796574 -0.391035944 0.083636224 0.036398906 0.074403420 0.025679423 0.996232808
1403638149395097088 -0.066369049 -0.400642097 0.092471369 0.037964914 0.074534252 0.025183866 0.996177256
1403638149445096960 -0.065289855 -0.428208351 0.091938242 0.038011733 0.073991239 0.025685262 0.996203125
1403638149495097088 -0.062538080 -0.443611741 0.098412730 0.038757086 0.073969461 0.024991743 0.996193647
1403638149545096960 -0.070211172 -0.459699690 0.108802319 0.039005425 0.074270487 0.024397537 0.996176302
1403638149595097088 -0.076784767 -0.479050577 0.116268322 0.038814213 0.074080884 0.023067519 0.996229589
1403638149645096960 -0.077974185 -0.482458591 0.121229559 0.039189417 0.072189197 0.022475470 0.996367276
1403638149695097088 -0.081867330 -0.504145980 0.126757383 0.038858410 0.068879880 0.020887837 0.996649027
1403638149745096960 -0.090940341 -0.513536692 0.142875656 0.039267853 0.066497296 0.018722001 0.996837795
1403638149795097088 -0.098463826 -0.527381718 0.149529800 0.038694032 0.063645765 0.017885568 0.997061729
1403638149845096960 -0.097784959 -0.530473948 0.158440039 0.038475621 0.060836691 0.016878137 0.997263074
1403638149895097088 -0.103419766 -0.536659420 0.168799832 0.039188553 0.058713123 0.016538136 0.997368276
1403638149945096960 -0.112250216 -0.538151205 0.178578183 0.038986076 0.057379518 0.015233406 0.997474611
1403638149995097088 -0.113283329 -0.547047257 0.186962187 0.038467597 0.055960063 0.013375022 0.997602046
1403638150045096960 -0.119742930 -0.543927848 0.203066409 0.038968831 0.056506667 0.009124815 0.997599721
1403638150095097088 -0.122086540 -0.547765255 0.207848236 0.038482428 0.056935754 0.004784347 0.997624457
1403638150145096960 -0.130274907 -0.542505562 0.225066558 0.038202938 0.058016974 -0.000329047 0.997584343
1403638150195097088 -0.132237002 -0.542737663 0.245588481 0.037920073 0.058805346 -0.004241005 0.997539997
1403638150245096960 -0.141969204 -0.532491207 0.247099489 0.037976574 0.060322419 -0.008306226 0.997421682
1403638150295097088 -0.149092004 -0.531690955 0.261503011 0.035511188 0.059940107 -0.008561948 0.997533381
1403638150345096960 -0.165234193 -0.534268558 0.282041997 0.032749295 0.059400789 -0.008161507 0.997663498
1403638150395097088 -0.169010058 -0.523163378 0.284557790 0.028268438 0.056885492 -0.005871549 0.997963190
1403638150445096960 -0.190178633 -0.519170940 0.305902123 0.022389030 0.052569311 -0.002229256 0.998363793
1403638150495097088 -0.202719048 -0.521659672 0.311450601 0.018572195 0.046844471 0.000464152 0.998729408
1403638150545096960 -0.218890294 -0.524771392 0.324115008 0.014616707 0.041724719 0.000920353 0.999021828
1403638150595097088 -0.235438645 -0.524890363 0.338169903 0.012616104 0.037117116 0.001408545 0.999230266
1403638150645096960 -0.254684865 -0.528199017 0.358898878 0.012013874 0.032928813 0.001626714 0.999384165
1403638150695097088 -0.270613909 -0.542117655 0.369756341 0.012552536 0.029400611 0.001474754 0.999487817
1403638150745096960 -0.294016123 -0.555352569 0.382789016 0.013226660 0.026388407 0.000011343 0.999564290
1403638150795097088 -0.304469973 -0.569363654 0.402232856 0.014584032 0.022494316 -0.002431156 0.999637663
1403638150845096960 -0.328939438 -0.581248164 0.412453651 0.016904632 0.017920520 -0.004996574 0.999684036
1403638150895097088 -0.349447548 -0.599933982 0.424885124 0.019324228 0.013948794 -0.007741409 0.999686003
1403638150945096960 -0.356584966 -0.608705521 0.444408983 0.022742273 0.009701447 -0.010130807 0.999642968
1403638150995097088 -0.382791340 -0.623139501 0.459141016 0.027388375 0.005398091 -0.012091279 0.999537170
1403638151045096960 -0.405902684 -0.629723012 0.480357587 0.028474350 0.001012634 -0.015647868 0.999471486
1403638151095097088 -0.431241125 -0.643676937 0.501113832 0.030844456 -0.005186190 -0.019919286 0.999312222
1403638151145096960 -0.443196118 -0.644667029 0.523555040 0.033880349 -0.013605379 -0.024670145 0.999028742
1403638151195097088 -0.469274849 -0.650453627 0.541130185 0.034989126 -0.023218127 -0.028932979 0.998698950
1403638151245096960 -0.496587068 -0.665226996 0.561707377 0.034152087 -0.034307774 -0.032987263 0.998282731
1403638151295097088 -0.526195884 -0.668528378 0.583532155 0.033505518 -0.045208443 -0.037012961 0.997729242
1403638151345096960 -0.551900983 -0.666549683 0.611121535 0.033339567 -0.056908481 -0.041647878 0.996953011
1403638151395097088 -0.581469774 -0.678453684 0.631627321 0.033039618 -0.069077782 -0.045826238 0.996010303
1403638151445096960 -0.611615479 -0.692981839 0.630113244 0.032509152 -0.081454240 -0.048898950 0.994945824
1403638151495097088 -0.639434457 -0.700333893 0.663378119 0.032970984 -0.093337782 -0.053086516 0.993671358
1403638151545096960 -0.661787868 -0.705465198 0.683726192 0.033624575 -0.104391225 -0.056262348 0.992374122
1403638151595097088 -0.679880738 -0.707651377 0.698852718 0.033814117 -0.113909774 -0.059832849 0.991111100
1403638151645096960 -0.715432882 -0.740297496 0.716030002 0.033604819 -0.121504411 -0.062946647 0.990022779
1403638151695097088 -0.727310658 -0.749549747 0.728716850 0.034219321 -0.128472790 -0.065426312 0.988960683
1403638151745096960 -0.755668104 -0.755025208 0.747973204 0.034608871 -0.133734271 -0.067000635 0.988143861
1403638151795097088 -0.789237261 -0.773492217 0.765774846 0.034101803 -0.137702897 -0.069573373 0.987438381
1403638151845096960 -0.808647394 -0.793776691 0.779370248 0.033846147 -0.141489789 -0.070275605 0.986861885
1403638151895097088 -0.842505455 -0.816341639 0.782560885 0.033194046 -0.143385440 -0.072057217 0.986481905
1403638151945096960 -0.872508109 -0.840651870 0.804804981 0.032575510 -0.144583225 -0.074357517 0.986156940
1403638151995097088 -0.906694055 -0.855165184 0.820036411 0.032498322 -0.145468324 -0.075210683 0.985964596
1403638152045096960 -0.936618686 -0.880604327 0.833285928 0.031907421 -0.146117076 -0.074859433 0.985914707
1403638152095097088 -0.963745058 -0.897657216 0.840841413 0.031802554 -0.146531910 -0.075101160 0.985838175
1403638152145096960 -1.002987266 -0.923634291 0.847124696 0.031271238 -0.145790026 -0.076436929 0.985862494
1403638152195097088 -1.042436123 -0.932763577 0.879864812 0.031840805 -0.145657852 -0.075875096 0.985907137
1403638152245096960 -1.068059921 -0.950755596 0.889964581 0.032338254 -0.145357788 -0.076878138 0.985857546
1403638152295097088 -1.083214998 -0.951114058 0.889689744 0.032653693 -0.144249469 -0.079139017 0.985831022
1403638152345096960 -1.116702557 -0.955694973 0.907088220 0.034062639 -0.143122479 -0.080196433 0.985862195
1403638152395097088 -1.143286943 -0.965726316 0.931059003 0.033921346 -0.142467722 -0.081417903 0.985861778
1403638152445096960 -1.181537867 -0.978653848 0.947730422 0.033383191 -0.141127780 -0.082611196 0.985973597
1403638152495097088 -1.215619802 -0.982798755 0.965347528 0.032991603 -0.139591694 -0.084108166 0.986078858
1403638152545096960 -1.258729696 -0.987934053 0.988771081 0.033454847 -0.139127448 -0.084422484 0.986101985
1403638152595097088 -1.273344398 -0.992358327 1.013383269 0.033212040 -0.140376031 -0.083261453 0.986032009
1403638152645096960 -1.312992573 -0.997790098 1.034847021 0.031384304 -0.141239941 -0.081632391 0.986104667
1403638152695097088 -1.355669975 -0.997890592 1.061324477 0.030435253 -0.143547148 -0.079513274 0.985974431
1403638152745096960 -1.417284131 -1.015726328 1.073706388 0.029347489 -0.145512953 -0.078694120 0.985784948
1403638152795097088 -1.454730988 -1.037727356 1.094358206 0.030048272 -0.150673196 -0.078163378 0.985030532
1403638152845096960 -1.516680002 -1.067216396 1.127521157 0.030410100 -0.156110644 -0.077405594 0.984232247
1403638152895097088 -1.538556576 -1.061635733 1.121600151 0.034003824 -0.163081810 -0.076187409 0.983078599
1403638152945096960 -1.586723804 -1.076150298 1.137843370 0.036852922 -0.169988602 -0.078042902 0.981659293
1403638152995097088 -1.631158829 -1.082295775 1.156742930 0.037457153 -0.177492693 -0.079851978 0.980161726
1403638153045096960 -1.678666472 -1.095223427 1.140377522 0.035443604 -0.182397947 -0.082309775 0.979132175
1403638153095097088 -1.716519117 -1.113614798 1.156432390 0.032491256 -0.189358726 -0.085014641 0.977680981
1403638153145096960 -1.770216703 -1.135568261 1.167691231 0.029288391 -0.193766579 -0.087699659 0.976680815
1403638153195097088 -1.800967455 -1.146205902 1.188638091 0.028344730 -0.199092582 -0.090171866 0.975411594
1403638153245096960 -1.845630527 -1.164749265 1.203078508 0.027333459 -0.202521458 -0.092452720 0.974520624
1403638153295097088 -1.877121329 -1.178814054 1.221979380 0.026634946 -0.207174599 -0.094491534 0.973365605
1403638153345096960 -1.939818501 -1.197559953 1.221956849 0.025513614 -0.210179821 -0.097935349 0.972410500
1403638153395097088 -1.964269638 -1.201347470 1.269254923 0.026402062 -0.218341380 -0.100748196 0.970298827
1403638153445096960 -2.010466576 -1.218633652 1.292351007 0.026267020 -0.224124402 -0.105270982 0.968502104
1403638153495097088 -2.051179647 -1.226638794 1.309776783 0.027037816 -0.229727969 -0.112759151 0.966322601
1403638153545096960 -2.124758244 -1.259027958 1.296831965 0.025338475 -0.232002988 -0.121600553 0.964751720
1403638153595097088 -2.134766579 -1.270655274 1.351905823 0.026556993 -0.243251845 -0.126569092 0.961303055
1403638153645096960 -2.201115608 -1.292885065 1.364481091 0.027359739 -0.249430910 -0.132489666 0.958896279
1403638153695097088 -2.244872570 -1.296911478 1.379776359 0.029420989 -0.258924067 -0.135490343 0.955894947
1403638153745096960 -2.303270340 -1.335919023 1.380588412 0.029029692 -0.267435819 -0.138241336 0.953165591
1403638153795097088 -2.368484497 -1.355595946 1.374378800 0.030179540 -0.273688167 -0.140796334 0.950978637
1403638153845096960 -2.406669378 -1.372328877 1.437807202 0.032547213 -0.284422368 -0.141669825 0.947615027
1403638153895097088 -2.504309177 -1.394829869 1.427763939 0.034409083 -0.287064582 -0.143512353 0.946474552
1403638153945096960 -2.570144653 -1.409052253 1.457957268 0.037400000 -0.292897552 -0.141777262 0.944834054
1403638153995097088 -2.626925945 -1.428066373 1.478981137 0.038568757 -0.297360361 -0.141983524 0.943360984
1403638154045096960 -2.681953430 -1.432149172 1.501291633 0.040642127 -0.301085383 -0.140967995 0.942243993
1403638154095097088 -2.737139702 -1.452296972 1.518488884 0.042343806 -0.303388566 -0.141330659 0.941375613
1403638154145096960 -2.779447079 -1.459828973 1.541568995 0.045985036 -0.306233197 -0.139947563 0.940489888
1403638154195097088 -2.842537403 -1.459815741 1.580471516 0.050787002 -0.307619929 -0.139693514 0.939827859
1403638154245096960 -2.897766829 -1.473891973 1.591346741 0.053743459 -0.307606101 -0.142090291 0.939308524
1403638154295097088 -2.951820612 -1.472097278 1.615169644 0.057015713 -0.307889491 -0.141922742 0.939047992
1403638154345096960 -3.059673309 -1.410411716 1.535946608 0.062744111 -0.299261689 -0.133241326 0.942736626
1403638154395097088 -3.113367319 -1.408501744 1.554926991 0.068973854 -0.299508423 -0.131305739 0.942494631
1403638154445096960 -3.158862591 -1.411916018 1.571023226 0.072654963 -0.300163239 -0.129508197 0.942258418
1403638154495097088 -3.218192101 -1.411942959 1.581802607 0.075420976 -0.299141467 -0.128278866 0.942534149
1403638154545096960 -3.273848057 -1.421886802 1.601039648 0.073904201 -0.299781114 -0.126800701 0.942651033
1403638154595097088 -3.332604647 -1.430727839 1.624401927 0.072048254 -0.301714182 -0.126606464 0.942204058
1403638154645096960 -3.397217274 -1.441069007 1.649510503 0.068734542 -0.304063886 -0.127195865 0.941616654
1403638154695097088 -3.448744297 -1.429109097 1.633841395 0.065344729 -0.305883557 -0.128576800 0.941080928
1403638154745096960 -3.502963066 -1.433362603 1.638780117 0.061810724 -0.308562189 -0.132667556 0.939876676
1403638154795097088 -3.559686184 -1.441409230 1.653565288 0.059222341 -0.311143517 -0.136900768 0.938584387
1403638154845096960 -3.612405300 -1.448527694 1.643887758 0.057800613 -0.312847167 -0.141451746 0.937431157
1403638154895097088 -3.665472984 -1.450044513 1.649574280 0.057748962 -0.315146416 -0.144963294 0.936126828
1403638154945096960 -3.707687378 -1.460787058 1.655083895 0.058051825 -0.318304569 -0.149435177 0.934334695
1403638154995097088 -3.770445824 -1.471893549 1.651581526 0.058822371 -0.321754932 -0.152425244 0.932620108
1403638155045096960 -3.820538998 -1.483424425 1.657007813 0.060222741 -0.327464640 -0.154440194 0.930208802
1403638155095097088 -3.884781837 -1.502428174 1.631131172 0.060388993 -0.331958950 -0.157489315 0.928091347
1403638155145096960 -3.941547155 -1.513762116 1.622543573 0.062192403 -0.337533355 -0.158650339 0.925760984
1403638155195097088 -3.981135130 -1.517422915 1.647692680 0.063740030 -0.344428778 -0.158600301 0.923120797
1403638155245096960 -4.053730488 -1.532109857 1.615078330 0.065878622 -0.347795248 -0.159066215 0.921627045
1403638155295097088 -4.110870838 -1.541181564 1.602234006 0.068477735 -0.351285338 -0.159485102 0.920040190
1403638155345096960 -4.166850090 -1.547898889 1.599679470 0.071526974 -0.355072051 -0.161044955 0.918080747
1403638155395097088 -4.214975834 -1.546934128 1.592504740 0.074891947 -0.359780550 -0.162738755 0.915677488
1403638155445096960 -4.270048141 -1.548071742 1.591031551 0.077893846 -0.364043862 -0.165863171 0.913178027
1403638155495097088 -4.326199055 -1.551422715 1.581455708 0.078540437 -0.369196177 -0.168143868 0.910633445
1403638155545096960 -4.391224861 -1.544056654 1.560362577 0.078884251 -0.376562744 -0.167367637 0.907725632
1403638155595097088 -4.450899124 -1.537527800 1.556690454 0.079319291 -0.384233981 -0.167510509 0.904440701
1403638155645096960 -4.498733521 -1.528502107 1.551304817 0.080238894 -0.394622415 -0.165099621 0.900320530
1403638155695097088 -4.557423115 -1.522404432 1.527343750 0.081280403 -0.404651582 -0.163872257 0.895989120
1403638155745096960 -4.597541809 -1.512302995 1.522363901 0.081578739 -0.414947957 -0.164507508 0.891123116
1403638155795097088 -4.648185253 -1.503199100 1.519776106 0.080722563 -0.425253093 -0.166730583 0.885914564
1403638155845096960 -4.714612007 -1.490384579 1.496712208 0.078377388 -0.435539275 -0.168487966 0.880780518
1403638155895097088 -4.763383865 -1.475555897 1.477494717 0.074301884 -0.445537716 -0.173097581 0.875221491
1403638155945096960 -4.810206413 -1.461254835 1.466377974 0.068399586 -0.456175268 -0.178737432 0.869067609
1403638155995097088 -4.856847763 -1.452060223 1.443523645 0.061351396 -0.466349810 -0.185351178 0.862785459
1403638156045096960 -4.878034592 -1.446122885 1.443626642 0.054684743 -0.477728456 -0.191644818 0.855603516
1403638156095097088 -4.918122292 -1.429269791 1.441073895 0.049434152 -0.488783717 -0.198879212 0.847993970
1403638156145096960 -4.950945377 -1.429646134 1.434663177 0.045411490 -0.499469578 -0.203315005 0.840910733
1403638156195097088 -5.034952164 -1.410167575 1.368816614 0.042143364 -0.507234693 -0.205813438 0.835809588
1403638156245096960 -5.029598236 -1.425037861 1.397471189 0.039121971 -0.517690241 -0.209426254 0.828617513
1403638156295097088 -5.116966248 -1.395499468 1.317508698 0.036123067 -0.523055732 -0.215457574 0.823823929
1403638156345096960 -5.151651859 -1.399927974 1.302734613 0.032336824 -0.530027330 -0.219631210 0.818405449
1403638156395097088 -5.182414532 -1.392340422 1.291656137 0.029592471 -0.535888970 -0.221662059 0.814133406
1403638156445096960 -5.224648952 -1.396291494 1.262340069 0.026013641 -0.539762676 -0.223963231 0.811061025
1403638156495097088 -5.260383606 -1.388208866 1.242611408 0.023455024 -0.543286800 -0.225052208 0.808480561
1403638156545096960 -5.314540863 -1.387931228 1.240121603 0.022853831 -0.546694934 -0.226690188 0.805738091
1403638156595097088 -5.351066113 -1.372444034 1.242015123 0.022821996 -0.549814403 -0.226364717 0.803705335
1403638156645096960 -5.390442371 -1.360277772 1.222469807 0.022775717 -0.550749242 -0.227496162 0.802746534
1403638156695097088 -5.421650410 -1.363198996 1.210645318 0.021701200 -0.551934719 -0.227944613 0.801834345
1403638156745096960 -5.505594254 -1.341104746 1.188284278 0.022909593 -0.551476538 -0.229216814 0.801753283
1403638156795097088 -5.596528053 -1.314254045 1.156337976 0.023224438 -0.550018907 -0.229622662 0.802628994
1403638156845096960 -5.646630764 -1.299864292 1.148986936 0.023108918 -0.549399734 -0.229508251 0.803088963
1403638156895097088 -5.648750782 -1.296773076 1.166617155 0.022842849 -0.550152540 -0.229108810 0.802695215
1403638156945096960 -5.724095345 -1.290693879 1.130812526 0.022468621 -0.547862172 -0.230257347 0.803942621
1403638156995097088 -5.784411430 -1.279166222 1.121832490 0.022368029 -0.546685100 -0.229921892 0.804842234
1403638157045096960 -5.837539673 -1.275946259 1.121623993 0.020901788 -0.545662224 -0.230378851 0.805444896
1403638157095097088 -5.890455246 -1.261595964 1.118777990 0.019604513 -0.544562936 -0.230130076 0.806292117
1403638157145096960 -5.939543724 -1.258507133 1.116935968 0.017563306 -0.543283045 -0.230867058 0.806991577
1403638157195097088 -5.990991592 -1.258889794 1.116431355 0.015890239 -0.541693032 -0.232243180 0.807699978
1403638157245096960 -6.050132275 -1.259196043 1.100081444 0.015638007 -0.540691376 -0.231972054 0.808453619
1403638157295097088 -6.100781441 -1.259359002 1.081166267 0.016454577 -0.540802896 -0.231616244 0.808464885
1403638157345096960 -6.166994095 -1.265206575 1.091800451 0.018587196 -0.542250276 -0.232084543 0.807314038
1403638157395097088 -6.253936768 -1.268988371 1.071640968 0.021217817 -0.541687131 -0.234354347 0.806971431
1403638157445096960 -6.308914185 -1.269434571 1.063791513 0.025169605 -0.542146206 -0.235610068 0.806183517
1403638157495097088 -6.366857052 -1.273317575 1.061052203 0.028190147 -0.544313014 -0.235998183 0.804508209
1403638157545096960 -6.399588585 -1.274754763 1.070079923 0.031534791 -0.548229873 -0.236181393 0.801665723
1403638157595097088 -6.459957600 -1.271353841 1.070948362 0.035408709 -0.552883983 -0.236283347 0.798270464
1403638157645096960 -6.555213928 -1.268187642 1.055566788 0.040332936 -0.557301641 -0.237902626 0.794474959
1403638157695097088 -6.586631298 -1.275933027 1.057669044 0.045118496 -0.563837886 -0.240502059 0.788802862
1403638157745096960 -6.645612240 -1.283659577 1.060159445 0.049053591 -0.570469081 -0.244686946 0.782487750
1403638157795097088 -6.701094627 -1.281980038 1.047281981 0.051097941 -0.577670455 -0.247403935 0.776193976
1403638157845096960 -6.767796040 -1.291186213 1.043188810 0.051653221 -0.586294055 -0.250357598 0.768708229
1403638157895097088 -6.855733871 -1.276784301 1.017415643 0.052233614 -0.594651103 -0.251286715 0.761916459
1403638157945096960 -6.945871353 -1.287197709 0.999935806 0.050844610 -0.602598429 -0.253361106 0.755048394
1403638157995097088 -7.008081436 -1.288913250 0.987856030 0.051226005 -0.609407485 -0.255448163 0.748828828
1403638158045096960 -7.068462372 -1.298398852 0.977184892 0.046721928 -0.616120160 -0.257518858 0.742897689
1403638158095097088 -7.120585442 -1.299726725 0.968563795 0.043441590 -0.622536957 -0.257114559 0.737870336
1403638158145096960 -7.188124180 -1.303488970 0.954260826 0.040747199 -0.627632499 -0.256715477 0.733835340
1403638158195097088 -7.242665291 -1.302392125 0.946327746 0.037641138 -0.632469296 -0.255375057 0.730307639
1403638158245096960 -7.307026863 -1.307692885 0.938752890 0.036864918 -0.635539770 -0.256143838 0.727406681
1403638158295097088 -7.367559910 -1.304214358 0.933948457 0.037942369 -0.637812257 -0.256953537 0.725072980
1403638158345096960 -7.419928551 -1.303896427 0.931784809 0.038843006 -0.638525546 -0.259752929 0.723398089
1403638158395097088 -7.487473488 -1.301505804 0.922098160 0.040029593 -0.639170885 -0.260953367 0.722330630
1403638158445096960 -7.534850597 -1.300504804 0.923394203 0.043228943 -0.639209986 -0.263329029 0.721248686
1403638158495097088 -7.606234074 -1.295580268 0.913926780 0.045968499 -0.638885438 -0.265056193 0.720734060
1403638158545096960 -7.660985470 -1.288301945 0.909447074 0.048975497 -0.638426483 -0.265939146 0.720617354
1403638158595097088 -7.717759132 -1.287576079 0.912108839 0.050407030 -0.638172328 -0.266988844 0.720355570
1403638158645096960 -7.781458378 -1.281516314 0.905315101 0.052030254 -0.637865424 -0.266562074 0.720669985
1403638158695097088 -7.830508709 -1.278293729 0.904297233 0.050963141 -0.638241291 -0.264855117 0.721042693
1403638158745096960 -7.894467354 -1.271296620 0.895734072 0.048982620 -0.638348997 -0.263249725 0.721672237
1403638158795097088 -7.950261116 -1.269547343 0.886393070 0.044422418 -0.637940526 -0.262624443 0.722555816
1403638158845096960 -8.008972168 -1.266306639 0.875156999 0.039830618 -0.637294233 -0.262053728 0.723600328
1403638158895097088 -8.067419052 -1.261395693 0.874246359 0.035721257 -0.636916161 -0.261808872 0.724236071
1403638158945096960 -8.125360489 -1.263166904 0.864532053 0.032085642 -0.636567831 -0.261262625 0.724909484
1403638158995097088 -8.169557571 -1.268995762 0.854714394 0.028466433 -0.635086000 -0.263244629 0.725642979
1403638159045096960 -8.229923248 -1.269230843 0.842266619 0.023612272 -0.633342385 -0.265627712 0.726472139
1403638159095097088 -8.293040276 -1.273620367 0.840416133 0.019115733 -0.631712198 -0.268895805 0.726821363
1403638159145096960 -8.343255997 -1.279451609 0.836013317 0.012231941 -0.629597902 -0.272570759 0.727435291
1403638159195097088 -8.410374641 -1.284528732 0.824360907 0.007285825 -0.626746655 -0.277945787 0.727929711
1403638159245096960 -8.454819679 -1.288710117 0.824035823 0.005758676 -0.625767291 -0.279333472 0.728254735
1403638159295097088 -8.532307625 -1.292318344 0.813287377 0.008814699 -0.626475453 -0.276006550 0.728883505
1403638159345096960 -8.598931313 -1.296799421 0.809531808 0.014199606 -0.629383624 -0.268255293 0.729187012
1403638159395097088 -8.658566475 -1.304057837 0.805665255 0.022017207 -0.632480323 -0.260152727 0.729249239
1403638159445096960 -8.734133720 -1.305075169 0.802928030 0.030963387 -0.636218190 -0.250160605 0.729168892
1403638159495097088 -8.783151627 -1.312091827 0.797793031 0.038007416 -0.639989614 -0.239482179 0.729120731
1403638159545096960 -8.837939262 -1.327404976 0.799440742 0.042107299 -0.644809723 -0.228245825 0.728252232
1403638159595097088 -8.928630829 -1.327219486 0.790827274 0.043145828 -0.648846984 -0.216235742 0.728270650
1403638159645096960 -8.990959167 -1.338625431 0.787032485 0.042997602 -0.652363598 -0.207300410 0.727735817
1403638159695097088 -9.048513412 -1.354597688 0.788630486 0.042676907 -0.655155718 -0.200135231 0.727252007
1403638159745096960 -9.107842445 -1.366191268 0.785843074 0.040530078 -0.656837821 -0.196278796 0.726908505
1403638159795097088 -9.151660919 -1.391413927 0.792313039 0.044336800 -0.657027423 -0.197034970 0.726310134
1403638159845096960 -9.195487022 -1.412917852 0.795063138 0.048419543 -0.656276882 -0.199213952 0.726133585
1403638159895097088 -9.256912231 -1.426779032 0.795877099 0.054850757 -0.653600812 -0.205350652 0.726380348
1403638159945096960 -9.290792465 -1.451870322 0.799421251 0.060318664 -0.650905490 -0.212162241 0.726409554
1403638159995097088 -9.334982872 -1.475218177 0.803991616 0.064264774 -0.649270892 -0.217295647 0.726016521
1403638160045096960 -9.380139351 -1.512537360 0.810877860 0.066492908 -0.647903860 -0.221990764 0.725616515
1403638160095097088 -9.412825584 -1.539481878 0.808644116 0.065520078 -0.646429121 -0.225991905 0.725785255
1403638160145096960 -9.448267937 -1.577703238 0.817230225 0.063483395 -0.645403445 -0.230863556 0.725345612
1403638160195097088 -9.480320930 -1.616577506 0.820346057 0.057599150 -0.643278778 -0.238559678 0.725233793
1403638160245096960 -9.500457764 -1.654713869 0.824907243 0.050675686 -0.641166151 -0.245749325 0.725220799
1403638160295097088 -9.538557053 -1.688017845 0.821418107 0.044275589 -0.639071167 -0.251713812 0.725443184
1403638160345096960 -9.570648193 -1.728233337 0.817703485 0.040252261 -0.636728466 -0.257677555 0.725643754
1403638160395097088 -9.596390724 -1.772057533 0.823237479 0.036927730 -0.635692120 -0.261782885 0.725259602
1403638160445096960 -9.631981850 -1.808995485 0.818560541 0.034366488 -0.634884417 -0.263034940 0.725639939
1403638160495097088 -9.658516884 -1.849007368 0.818851650 0.032941349 -0.634342611 -0.264036506 0.725816131
1403638160545096960 -9.693047523 -1.883934021 0.819832981 0.032690383 -0.633967042 -0.264824986 0.725868344
1403638160595097088 -9.720507622 -1.925825834 0.821405172 0.031552009 -0.633746743 -0.265448600 0.725883305
1403638160645096960 -9.755086899 -1.961101055 0.824867487 0.030887356 -0.633736134 -0.265223473 0.726003408
1403638160695097088 -9.794619560 -1.993165970 0.822360158 0.032521237 -0.633562088 -0.264606506 0.726309121
1403638160745096960 -9.829135895 -2.023936749 0.821511924 0.033090763 -0.634975135 -0.260494322 0.726535797
1403638160795097088 -9.853767395 -2.070689678 0.833376050 0.033524696 -0.637346983 -0.254404604 0.726597011
1403638160845096960 -9.895602226 -2.092171907 0.831952095 0.037322428 -0.638015985 -0.245216832 0.728979647
1403638160895097088 -9.934294701 -2.122033596 0.834018290 0.040597867 -0.637760222 -0.235445291 0.732242525
1403638160945096960 -9.969355583 -2.154980421 0.836303651 0.044823159 -0.635367692 -0.227546558 0.736560524
1403638160995097088 -10.005198479 -2.184064627 0.850566030 0.048607960 -0.631398380 -0.221504524 0.741558552
1403638161045096960 -10.037536621 -2.227860451 0.855756402 0.051117297 -0.626201510 -0.217564821 0.746943235
1403638161095097088 -10.065032959 -2.248876572 0.869962931 0.052235328 -0.619852602 -0.212169260 0.753683209
1403638161145096960 -10.094574928 -2.253199577 0.870244265 0.054795284 -0.611206591 -0.208907008 0.761434019
1403638161195097088 -10.130837440 -2.321301222 0.886223793 0.053443696 -0.602157354 -0.211355627 0.768035889
1403638161245096960 -10.135828018 -2.327486515 0.916150808 0.053377677 -0.592486382 -0.207432538 0.776583791
1403638161295097088 -10.153169632 -2.322954655 0.918740511 0.054671895 -0.580983758 -0.203140244 0.786258817
1403638161345096960 -10.171619415 -2.377052784 0.949608564 0.052138373 -0.570968032 -0.202833176 0.793810964
1403638161395097088 -10.195258141 -2.402300835 0.964466095 0.049835660 -0.560749352 -0.203244880 0.801104248
1403638161445096960 -10.217041969 -2.431993961 0.972655773 0.045153182 -0.551004946 -0.203824475 0.807966769
1403638161495097088 -10.245707512 -2.455713272 0.989619493 0.041843217 -0.542927384 -0.205878839 0.813076198
1403638161545096960 -10.248818398 -2.482398510 1.022481918 0.040006779 -0.537554085 -0.206736013 0.816514075
1403638161595097088 -10.285945892 -2.543391705 1.027250051 0.036348540 -0.531728804 -0.208684221 0.819996476
1403638161645096960 -10.326494217 -2.531565666 1.051871061 0.036183346 -0.526611090 -0.203937471 0.824488342
1403638161695097088 -10.329164505 -2.553870916 1.083873272 0.034583014 -0.525608301 -0.201255053 0.825854897
1403638161745096960 -10.350259781 -2.602284908 1.100902796 0.032423496 -0.524069726 -0.199825838 0.827266157
1403638161795097088 -10.401442528 -2.595802069 1.104435205 0.034016903 -0.520287752 -0.193231091 0.831146955
1403638161845096960 -10.425321579 -2.612001896 1.114022732 0.037755053 -0.516836345 -0.190806657 0.833695114
1403638161895097088 -10.455494881 -2.621090174 1.117439270 0.040848922 -0.512549520 -0.186146975 0.837241709
1403638161945096960 -10.466746330 -2.645112753 1.152967691 0.042614564 -0.509392381 -0.183421925 0.839678347
1403638161995097088 -10.501752853 -2.647411585 1.164989948 0.044345900 -0.504672468 -0.180629462 0.843037426
1403638162045096960 -10.524302483 -2.687530041 1.205429554 0.044594388 -0.502263725 -0.180410624 0.844508410
1403638162095097088 -10.539375305 -2.705123425 1.230806589 0.044315588 -0.499755293 -0.178832173 0.846345007
1403638162145096960 -10.568305969 -2.726253510 1.253131151 0.042637523 -0.497258663 -0.177563652 0.848166823
1403638162195097088 -10.585398674 -2.756408215 1.280900478 0.039476387 -0.496157497 -0.176247582 0.849238575
1403638162245096960 -10.604457855 -2.784533978 1.309307575 0.036913313 -0.494990528 -0.175585717 0.850171447
1403638162295097088 -10.624641418 -2.809860229 1.330072880 0.035054296 -0.493310601 -0.174579784 0.851432741
1403638162345096960 -10.642164230 -2.835644722 1.354791880 0.032731943 -0.493500113 -0.172067493 0.851926625
1403638162395097088 -10.659948349 -2.857306004 1.388271332 0.033342846 -0.493752390 -0.169202492 0.852330565
1403638162445096960 -10.679054260 -2.884829998 1.419464588 0.034074437 -0.493919849 -0.167549148 0.852531195
1403638162495097088 -10.699066162 -2.912311554 1.454374790 0.036250968 -0.493343443 -0.167440951 0.852796376
1403638162545096960 -10.715687752 -2.937484741 1.486912489 0.038191460 -0.492783546 -0.168545216 0.852817893
1403638162595097088 -10.740889549 -2.959193707 1.511543274 0.040036593 -0.490844637 -0.171305761 0.853301227
1403638162645096960 -10.738154411 -2.994902849 1.551469088 0.041783579 -0.491186291 -0.174361214 0.852401495
1403638162695097088 -10.766078949 -3.023083925 1.589693069 0.043135710 -0.489968210 -0.177173734 0.852455199
1403638162745096960 -10.785698891 -3.052304268 1.620978832 0.043503523 -0.489033669 -0.179757595 0.852432251
1403638162795097088 -10.797148705 -3.082024097 1.651768208 0.041629847 -0.488739312 -0.178364590 0.852987051
1403638162845096960 -10.817945480 -3.117821932 1.686786175 0.040310070 -0.486997306 -0.177165046 0.854295790
1403638162895097088 -10.833802223 -3.149778366 1.721040249 0.040846977 -0.486134261 -0.172511831 0.855712950
1403638162945096960 -10.849451065 -3.196353436 1.754290342 0.041111376 -0.485875189 -0.166356146 0.857065201
1403638162995097088 -10.862043381 -3.243879557 1.783046722 0.045853477 -0.484998554 -0.161928445 0.858168483
1403638163045096960 -10.874058723 -3.274410725 1.816803932 0.051432092 -0.484161139 -0.156698346 0.859295309
1403638163095097088 -10.895099640 -3.308360338 1.852033615 0.054961920 -0.482032597 -0.151166126 0.861262202
1403638163145096960 -10.908986092 -3.333720684 1.884243011 0.056888051 -0.477867931 -0.148940876 0.863841772
1403638163195097088 -10.920814514 -3.365567207 1.926986217 0.056978151 -0.472446293 -0.148505926 0.866887510
1403638163245096960 -10.935870171 -3.391559601 1.973530769 0.057681590 -0.465491742 -0.149021015 0.870507300
1403638163295097088 -10.937242508 -3.406081438 2.017710209 0.059694268 -0.458172917 -0.150224879 0.874040425
1403638163345096960 -10.944913864 -3.436093330 2.060291529 0.060938306 -0.450138748 -0.150350869 0.878098071
1403638163395097088 -10.960245132 -3.466720343 2.112484217 0.061834089 -0.441546023 -0.149555013 0.882523060
1403638163445096960 -10.961406708 -3.477867126 2.144348860 0.063800924 -0.432503641 -0.147055224 0.887268186
1403638163495097088 -10.982025146 -3.503130913 2.199709892 0.063267872 -0.425362021 -0.145251542 0.891047895
1403638163545096960 -10.997226715 -3.507894516 2.249068260 0.065964028 -0.418777376 -0.142734721 0.894371867
1403638163595097088 -10.996715546 -3.543881178 2.279133797 0.063100621 -0.414105117 -0.141724154 0.896911085
1403638163645096960 -11.003084183 -3.562151194 2.332766533 0.064525180 -0.409776300 -0.140636727 0.898966789
1403638163695097088 -11.009082794 -3.580206633 2.361272812 0.066031016 -0.405153871 -0.139463052 0.901132762
1403638163745096960 -11.010661125 -3.607700825 2.402677536 0.066328086 -0.402808309 -0.138955280 0.902240276
1403638163795097088 -11.007884979 -3.637727022 2.443174362 0.068057857 -0.400940567 -0.138450623 0.903020620
1403638163845096960 -11.009449959 -3.674585342 2.481959343 0.067803338 -0.400308043 -0.136282325 0.903649986
1403638163895097088 -11.006916046 -3.707189560 2.517129421 0.068259127 -0.399906337 -0.134595275 0.904046297
1403638163945096960 -11.006933212 -3.744234324 2.552277565 0.066268750 -0.399689734 -0.133723319 0.904419482
1403638163995097088 -11.004755020 -3.799300909 2.587002754 0.062052157 -0.401216269 -0.129731700 0.904624045
1403638164045096960 -11.003710747 -3.815140009 2.620926857 0.062309161 -0.401568502 -0.128657654 0.904603481
1403638164095097088 -11.001059532 -3.855078697 2.647707939 0.061282143 -0.402592510 -0.126496762 0.904523253
1403638164145096960 -10.988075256 -3.914919615 2.674188137 0.059621409 -0.404216200 -0.125067741 0.904108763
1403638164195097088 -10.990303040 -3.939082384 2.716270447 0.060945988 -0.405505329 -0.122109711 0.903847456
1403638164245096960 -10.974201202 -3.995970964 2.739423275 0.061131433 -0.406561077 -0.121407479 0.903455138
1403638164295097088 -10.966104507 -4.035391331 2.772552490 0.061887484 -0.408026010 -0.119681060 0.902973473
1403638164345096960 -10.968343735 -4.059485435 2.830188513 0.064558037 -0.409374714 -0.118227154 0.902367413
1403638164395097088 -10.949565887 -4.102194786 2.853360891 0.064767279 -0.409892380 -0.117968693 0.902151167
1403638164445096960 -10.937580109 -4.135329723 2.893700123 0.065936744 -0.410701722 -0.117829829 0.901716471
1403638164495097088 -10.922380447 -4.174787998 2.932988644 0.064283654 -0.411891311 -0.116845466 0.901421249
1403638164545096960 -10.919560432 -4.201149464 2.985224247 0.064735755 -0.412872732 -0.115362152 0.901130915
1403638164595097088 -10.894777298 -4.242140770 3.029592037 0.063133582 -0.414005667 -0.113610707 0.900947332
1403638164645096960 -10.884940147 -4.275844574 3.070084572 0.062080782 -0.412589401 -0.111906908 0.901882946
1403638164695097088 -10.864597321 -4.310498714 3.107922554 0.062717892 -0.408830017 -0.112598240 0.903463364
1403638164745096960 -10.852830887 -4.326919556 3.161607742 0.066712722 -0.405243993 -0.113224894 0.904713690
1403638164795097088 -10.831186295 -4.354146004 3.204825878 0.072808072 -0.399932325 -0.117785193 0.906024158
1403638164845096960 -10.810624123 -4.382241726 3.240545750 0.079421327 -0.393215477 -0.122626275 0.907764673
1403638164895097088 -10.794933319 -4.409573555 3.293368340 0.085783534 -0.387984037 -0.127815023 0.908720434
1403638164945096960 -10.773252487 -4.440162182 3.331190348 0.089319922 -0.383637577 -0.130304754 0.909870803
1403638164995097088 -10.747671127 -4.470511913 3.375162125 0.092057981 -0.382160753 -0.126834974 0.910709262
1403638165045096960 -10.721858978 -4.492211342 3.410360813 0.094295561 -0.381098896 -0.119334064 0.911938250
1403638165095097088 -10.708826065 -4.510586262 3.474490166 0.093868889 -0.380973518 -0.112502307 0.912902534
1403638165145096960 -10.663966179 -4.544935226 3.511053324 0.089562923 -0.378424227 -0.107431911 0.915003777
1403638165195097088 -10.639205933 -4.563955307 3.562834740 0.084390178 -0.374732316 -0.106216148 0.917154312
1403638165245096960 -10.607103348 -4.587752819 3.595865726 0.076584458 -0.370424926 -0.108371511 0.919334412
1403638165295097088 -10.576198578 -4.595332146 3.637703419 0.068705119 -0.367279291 -0.108810283 0.921165466
1403638165345096960 -10.576116562 -4.594454288 3.701150417 0.064919114 -0.366726965 -0.108367756 0.921712101
1403638165395097088 -10.542377472 -4.611854076 3.742120743 0.061689101 -0.365154088 -0.105375350 0.922904670
1403638165445096960 -10.511062622 -4.626832962 3.793170691 0.062368657 -0.362854213 -0.104179233 0.923901320
1403638165495097088 -10.472770691 -4.640407085 3.843263149 0.068581812 -0.361687720 -0.102459200 0.924110711
1403638165545096960 -10.439871788 -4.655202866 3.887452841 0.075783469 -0.359173924 -0.102007337 0.924578547
1403638165595097088 -10.410709381 -4.666082382 3.940937042 0.084646188 -0.357545078 -0.100795686 0.924573839
1403638165645096960 -10.371635437 -4.677411079 3.968988895 0.094253592 -0.354310542 -0.101866260 0.924772143
1403638165695097088 -10.331278801 -4.677804470 4.044344902 0.099583231 -0.362597734 -0.097473204 0.921468973
1403638165745096960 -10.292461395 -4.685501099 4.093806267 0.105410047 -0.360340655 -0.098950624 0.921548724
1403638165795097088 -10.252642632 -4.686950207 4.130497456 0.105780691 -0.358160824 -0.100967564 0.922137082
1403638165845096960 -10.213747025 -4.695918083 4.175206661 0.101331532 -0.356372595 -0.105296314 0.922845125
1403638165895097088 -10.171771049 -4.702869892 4.219232082 0.094937056 -0.355713546 -0.106256112 0.923669040
1403638165945096960 -10.125867844 -4.704941273 4.262079716 0.091185644 -0.354290575 -0.110530786 0.924092174
1403638165995097088 -10.077728271 -4.715452194 4.293017387 0.083716534 -0.353558362 -0.112445869 0.924848080
1403638166045096960 -10.032917023 -4.724153042 4.335516453 0.077534884 -0.353405476 -0.114921935 0.925140977
1403638166095097088 -9.984133720 -4.742567062 4.388425350 0.073428795 -0.353356034 -0.120447814 0.924791873
1403638166145096960 -9.940222740 -4.746981144 4.433591843 0.072902776 -0.353026688 -0.124720588 0.924392819
1403638166195097088 -9.892677307 -4.765278339 4.454540253 0.070943080 -0.352277249 -0.126971021 0.924524844
1403638166245096960 -9.851488113 -4.779918671 4.483866215 0.070737578 -0.352500737 -0.129771322 0.924066484
1403638166295097088 -9.809316635 -4.801660538 4.514031410 0.072364181 -0.352980107 -0.132008344 0.923440456
1403638166345096960 -9.775149345 -4.843011856 4.529089451 0.070107922 -0.351365447 -0.133883059 0.923960209
1403638166395097088 -9.706434250 -4.874528408 4.553168297 0.071399823 -0.352808505 -0.134907231 0.923162103
1403638166445096960 -9.667219162 -4.907095909 4.577625751 0.069776081 -0.353025109 -0.136156976 0.923019946
1403638166495097088 -9.630626678 -4.941952229 4.605201721 0.071675852 -0.354350686 -0.138238475 0.922056556
1403638166545096960 -9.594248772 -4.932729244 4.493906975 0.064548813 -0.362247080 -0.131635308 0.920479596
1403638166595097088 -9.555183411 -4.961787701 4.513900757 0.065914787 -0.362240255 -0.131816715 0.920359492
1403638166645096960 -9.517021179 -4.993424416 4.533708096 0.064428650 -0.362793565 -0.131015614 0.920361161
1403638166695097088 -9.472197533 -5.024473190 4.559142590 0.063163564 -0.364804029 -0.129064530 0.919929743
1403638166745096960 -9.433946609 -5.045016766 4.580412865 0.061236437 -0.366743267 -0.126304373 0.919672072
1403638166795097088 -9.392271042 -5.064817429 4.608942032 0.056087602 -0.369945168 -0.121093094 0.919418931
1403638166845096960 -9.353483200 -5.093739033 4.630455971 0.046764836 -0.372001290 -0.117439099 0.919584751
1403638166895097088 -9.309282303 -5.105618954 4.655879974 0.036947213 -0.374233216 -0.113953233 0.919564605
1403638166945096960 -9.283460617 -5.116144180 4.677470684 0.029872891 -0.373334706 -0.113602757 0.920229971
1403638166995097088 -9.252873421 -5.136914253 4.720024109 0.021578299 -0.373031408 -0.114554830 0.920466840
1403638167045096960 -9.217452049 -5.159718037 4.761709213 0.017419020 -0.373145550 -0.118162878 0.920052469
1403638167095097088 -9.178310394 -5.168051720 4.797104359 0.018327113 -0.372682571 -0.120926507 0.919863343
1403638167145096960 -9.147341728 -5.195799351 4.833884716 0.017902842 -0.371670246 -0.125116915 0.919720888
1403638167195097088 -9.118511200 -5.206456184 4.877282143 0.021498909 -0.370733708 -0.126170486 0.919877887
1403638167245096960 -9.087907791 -5.238985062 4.908839703 0.023094855 -0.368733287 -0.130368382 0.920057893
1403638167295097088 -9.080552101 -5.258213520 4.917167664 0.026324153 -0.364101231 -0.130378917 0.921812713
1403638167345096960 -9.058298111 -5.277785778 4.945555210 0.030094927 -0.362126827 -0.131671339 0.922291279
1403638167395097088 -9.042427063 -5.296014309 4.985261917 0.032667831 -0.361055791 -0.129642218 0.922910869
1403638167445096960 -9.025882721 -5.351614952 5.022020340 0.032108083 -0.360432774 -0.129994258 0.923124492
1403638167495097088 -8.993064880 -5.385326862 5.060998440 0.034443188 -0.361576319 -0.125562117 0.923206568
1403638167545096960 -9.034831047 -5.341879368 4.885168552 0.038784925 -0.349456459 -0.125103682 0.927752674
1403638167595097088 -9.010847092 -5.366095543 4.927833080 0.042772472 -0.350785464 -0.118713781 0.927915454
1403638167645096960 -8.983329773 -5.403977871 4.972002506 0.043946054 -0.352580011 -0.112590984 0.927943647
1403638167695097088 -8.966177940 -5.432418346 5.016976357 0.045417622 -0.351357281 -0.106509440 0.929053843
1403638167745096960 -8.939621925 -5.464643002 5.064821720 0.045891330 -0.349494398 -0.099893510 0.930467010
1403638167795097088 -8.909547806 -5.504705429 5.123324394 0.044489563 -0.348579019 -0.093328655 0.931559503
1403638167845096960 -8.878809929 -5.526794910 5.173623085 0.044565048 -0.344944507 -0.086672321 0.933549762
1403638167895097088 -8.884971619 -5.550788879 5.224375248 0.045276780 -0.335521013 -0.081341632 0.937421560
1403638167945096960 -8.863825798 -5.575161934 5.275303841 0.046017516 -0.329013318 -0.076505266 0.940095544
1403638167995097088 -8.835117340 -5.594689846 5.330781460 0.048009168 -0.321460068 -0.072210446 0.942944407
1403638168045096960 -8.484049797 -5.829149723 5.364393711 0.021879671 -0.351909339 -0.080252461 0.932330787
1403638168095097088 -8.462140083 -5.855150223 5.424687386 0.022345321 -0.346365601 -0.075499259 0.934789479
1403638168145096960 -8.437772751 -5.886306763 5.476845741 0.022931658 -0.339243174 -0.074522808 0.937461734
1403638168195097088 -8.412359238 -5.920749187 5.546193123 0.024242688 -0.333315969 -0.071579613 0.939781427
1403638168245096960 -8.389621735 -5.958351612 5.598605156 0.024685189 -0.324376643 -0.072748631 0.942803323
1403638168295097088 -8.357047081 -5.994242191 5.645292759 0.025541158 -0.314894855 -0.073351599 0.945943177
1403638168345096960 -8.075565338 -6.216636658 5.795084000 0.006539293 -0.334277421 -0.074380979 0.939512253
1403638168395097088 -8.051350594 -6.254601479 5.854094982 0.008738088 -0.325356156 -0.072292909 0.942783475
1403638168445096960 -8.032402992 -6.285541058 5.923803329 0.010559269 -0.316579759 -0.073416315 0.945661604
1403638168495097088 -7.977292061 -6.359750748 6.001619339 0.005885826 -0.311718136 -0.078836910 0.946880102
1403638168545096960 -7.948141098 -6.397677898 6.062722206 0.004474197 -0.303747743 -0.084781744 0.948962271
1403638168595097088 -7.926770210 -6.427022457 6.132889271 0.001460704 -0.296869427 -0.090197720 0.950647533
1403638168645096960 -7.826637268 -6.497219563 6.195221901 -0.002628489 -0.296058238 -0.097052410 0.950222850
1403638168695097088 -7.806546688 -6.530627251 6.265270233 -0.004628830 -0.290924639 -0.101429246 0.951343000
1403638168745096960 -7.782152653 -6.558946609 6.326896667 -0.005548587 -0.287650019 -0.103565283 0.952103436
1403638168795097088 -7.701455116 -6.639802933 6.393192768 -0.009447887 -0.289610773 -0.107647263 0.951024950
1403638168845096960 -7.684371948 -6.665719509 6.462879181 -0.011192806 -0.287925780 -0.108925715 0.951371968
1403638168895097088 -7.670691967 -6.694461823 6.530387878 -0.011612266 -0.286549777 -0.110896200 0.951554716
1403638168945096960 -7.663447380 -6.717370510 6.601416588 -0.012508725 -0.286219090 -0.111538090 0.951567888
1403638168995097088 -7.606598854 -6.793198586 6.684725761 -0.014328928 -0.289390922 -0.114212841 0.950264692
1403638169045096960 -7.592840195 -6.812997818 6.756554604 -0.010058608 -0.290986598 -0.113233253 0.949949384
1403638169095097088 -7.598690033 -6.826243401 6.828228474 -0.004137550 -0.293072373 -0.108423844 0.949913561
1403638169145096960 -7.582070351 -6.860153675 6.902231693 -0.001527190 -0.297050089 -0.104727328 0.949100137
1403638169195097088 -7.526441574 -6.920024395 7.003319740 -0.002031661 -0.304028094 -0.100959376 0.947296143
1403638169245096960 -7.575565815 -6.896765709 7.045241833 0.002061066 -0.303572744 -0.091995761 0.948354423
1403638169295097088 -7.534161568 -6.952740669 7.149143219 0.001213443 -0.308547109 -0.085223585 0.947382808
1403638169345096960 -7.500466347 -6.980860233 7.243433952 0.003092465 -0.312038869 -0.071093589 0.947400630
1403638169395097088 -7.497125149 -6.994546890 7.316759586 0.005857270 -0.311412722 -0.059179537 0.948412180
1403638169445096960 -7.512998581 -7.009022713 7.410335541 0.009014259 -0.308104366 -0.049766287 0.950007200
1403638169495097088 -7.521323204 -7.018207550 7.488470078 0.011817976 -0.302122205 -0.042378776 0.952253401
1403638169545096960 -7.528478622 -7.026055336 7.564225197 0.015290970 -0.295107901 -0.036975183 0.954625785
1403638169595097088 -7.498219490 -7.046473026 7.641044617 0.016901761 -0.287431389 -0.032864835 0.957087994
1403638169645096960 -7.505753517 -7.066047192 7.713038445 0.017950714 -0.276272297 -0.034417223 0.960295200
1403638169695097088 -7.489700317 -7.082802296 7.785728931 0.017882373 -0.264612466 -0.036368635 0.963502884
1403638169745096960 -7.476508141 -7.100564480 7.857288361 0.018452400 -0.252449811 -0.037231836 0.966717362
1403638169795097088 -7.474545479 -7.103185177 7.923670292 0.020895142 -0.237239748 -0.041221719 0.970351219
1403638169845096960 -7.462063313 -7.132967949 7.982962132 0.021647260 -0.221561521 -0.045888789 0.973825514
1403638169895097088 -7.438604832 -7.159921169 8.070793152 0.023428515 -0.207016155 -0.049350370 0.976811111
1403638169945096960 -7.406774998 -7.176783562 8.127938271 0.029413082 -0.192402154 -0.052570958 0.979465485
1403638169995097088 -7.393510818 -7.199178219 8.189891815 0.036533162 -0.177996114 -0.052404139 0.981955469
1403638170045096960 -7.353699684 -7.257689476 8.251691818 0.039510980 -0.168123767 -0.050570771 0.983674705
1403638170095097088 -7.326240540 -7.286466599 8.297662735 0.043017555 -0.156404972 -0.044704989 0.985742569
1403638170145096960 -7.307395458 -7.308167934 8.353290558 0.043604687 -0.144796103 -0.036965445 0.987808824
1403638170195097088 -7.292298317 -7.327893257 8.414408684 0.043421775 -0.133474186 -0.028797621 0.989681721
1403638170245096960 -7.266504288 -7.346379280 8.463950157 0.042480122 -0.122593343 -0.020420585 0.991337121
1403638170295097088 -7.304866314 -7.347074032 8.489584923 0.041621778 -0.107902192 -0.011395953 0.993224502
1403638170345096960 -7.232624054 -7.372806072 8.536257744 0.038006052 -0.101034768 -0.006170427 0.994137526
1403638170395097088 -7.211763859 -7.382037163 8.591142654 0.034389146 -0.089503810 0.000689224 0.995392382
1403638170445096960 -7.190364838 -7.394900322 8.639576912 0.031250395 -0.077713549 0.006520882 0.996464491
1403638170495097088 -7.171549797 -7.415551662 8.696671486 0.028090181 -0.067129493 0.015282297 0.997231722
1403638170545096960 -7.122286797 -7.425536633 8.736459732 0.028565207 -0.059412375 0.025094384 0.997509122
1403638170595097088 -7.106041908 -7.445993423 8.796474457 0.029810064 -0.049274299 0.033383418 0.997781992
1403638170645096960 -7.064409256 -7.458369255 8.828663826 0.033012107 -0.039452169 0.040179834 0.997867346
1403638170695097088 -7.024074078 -7.455695152 8.821413040 0.036424138 -0.030209394 0.044568822 0.997884929
1403638170745096960 -6.998081684 -7.474138260 8.858461380 0.036463924 -0.019469561 0.049450025 0.997920871
1403638170795097088 -6.958053589 -7.484076500 8.898794174 0.038064007 -0.009003308 0.052620035 0.997848272
1403638170845096960 -6.932135582 -7.506850719 8.925258636 0.037427016 0.002179847 0.056483194 0.997699440
1403638170895097088 -6.897614002 -7.514844418 8.948543549 0.037786286 0.013692224 0.058659345 0.997468710
1403638170945096960 -6.851624012 -7.535035610 8.977484703 0.036130339 0.024267243 0.061900474 0.997132897
1403638170995097088 -6.855287075 -7.508753777 8.978720665 0.038996436 0.037416991 0.064312883 0.996465325
1403638171045096960 -6.816512108 -7.514680862 9.006296158 0.040589776 0.047831871 0.067454122 0.995748222
1403638171095097088 -6.773736477 -7.524432182 9.032825470 0.041518979 0.056753092 0.070780970 0.995010257
1403638171145096960 -6.722790241 -7.529632092 9.050663948 0.042857833 0.063804246 0.073206775 0.994350553
1403638171195097088 -6.695462227 -7.546486378 9.075542450 0.043010063 0.071451664 0.077362075 0.993508935
1403638171245096960 -6.684402466 -7.548290730 9.097463608 0.044447519 0.078506097 0.080162473 0.992690921
1403638171295097088 -6.630052567 -7.547266483 9.134847641 0.045952771 0.082662225 0.081824929 0.992149174
1403638171345096960 -6.512546062 -7.594939709 9.164629936 0.043957632 0.082223147 0.083057664 0.992173612
1403638171395097088 -6.567334652 -7.573554516 9.081326485 0.045620732 0.089688100 0.085952707 0.991204798
1403638171445096960 -6.511503220 -7.571441174 9.092878342 0.046231158 0.093320951 0.087377638 0.990716457
1403638171495097088 -6.482451439 -7.585965157 9.094721794 0.046719953 0.098059312 0.089749873 0.990023553
1403638171545096960 -6.407453537 -7.565416813 9.107676506 0.049876358 0.098821051 0.093360409 0.989459753
1403638171595097088 -6.360995293 -7.566190720 9.119468689 0.051260713 0.103317760 0.094826192 0.988790035
1403638171645096960 -6.312018394 -7.565069675 9.112754822 0.052469689 0.106944017 0.098882787 0.987943351
1403638171695097088 -6.257444382 -7.557752132 9.117936134 0.054300733 0.111345991 0.103324346 0.986903012
1403638171745096960 -6.197691917 -7.558846474 9.114679337 0.055136625 0.116538502 0.106360942 0.985934138
1403638171795097088 -6.046831131 -7.523029804 9.165217400 0.057843708 0.116843000 0.109054752 0.985448599
1403638171845096960 -6.043896675 -7.551238537 9.100379944 0.057380252 0.122743279 0.114778243 0.984107494
1403638171895097088 -5.995538712 -7.549888611 9.088527679 0.059617445 0.127732620 0.118232250 0.982929945
1403638171945096960 -5.938979149 -7.541301727 9.071138382 0.063545182 0.133066863 0.117828012 0.982024312
1403638171995097088 -5.881885529 -7.533666134 9.057078362 0.064094909 0.139030308 0.115963429 0.981384158
1403638172045096960 -5.785171986 -7.513209820 9.022779465 0.065653026 0.140819222 0.115310960 0.981102943
1403638172095097088 -5.737442970 -7.501571178 8.981644630 0.065366335 0.145465538 0.112160578 0.980809391
1403638172145096960 -5.652213573 -7.489435196 8.956533432 0.065384731 0.147381008 0.111818254 0.980561256
1403638172195097088 -5.554453373 -7.479525089 8.920895576 0.063643791 0.147617713 0.111588933 0.980666339
1403638172245096960 -5.478278160 -7.474245071 8.978252411 0.062601820 0.151555225 0.112951927 0.979976475
1403638172295097088 -5.405114174 -7.465965271 8.937170982 0.060659874 0.152928382 0.112843856 0.979897738
1403638172345096960 -5.333533287 -7.440971851 8.899985313 0.060829867 0.154144496 0.111605234 0.979838490
1403638172395097088 -5.263090134 -7.417573452 8.860622406 0.060636517 0.154668391 0.111850299 0.979739964
1403638172445096960 -5.190371513 -7.381693363 8.811875343 0.062398534 0.154551968 0.112133689 0.979615271
1403638172495097088 -5.108607292 -7.357851982 8.768365860 0.063740328 0.153320670 0.113596469 0.979553819
1403638172545096960 -5.048308372 -7.333908081 8.764021873 0.065444723 0.153474316 0.113292716 0.979452550
1403638172595097088 -4.970199585 -7.298236847 8.720393181 0.066824369 0.151952565 0.113641813 0.979556262
1403638172645096960 -4.889401436 -7.254027367 8.656857491 0.067965291 0.149932817 0.115497746 0.979571939
1403638172695097088 -4.821144581 -7.214862347 8.602931976 0.067348644 0.149162024 0.115701467 0.979708135
1403638172745096960 -4.756339073 -7.185202599 8.537722588 0.065933220 0.148928776 0.117053203 0.979679286
1403638172795097088 -4.681327343 -7.138170719 8.538841248 0.066679694 0.147774011 0.116361633 0.979886055
1403638172845096960 -4.597990513 -7.088505268 8.481696129 0.067368180 0.145048797 0.118401289 0.980001807
1403638172895097088 -4.510742664 -7.028030396 8.372435570 0.066501804 0.143748686 0.118170992 0.980280280
1403638172945096960 -4.417433739 -6.961430550 8.292850494 0.064905971 0.140030324 0.120571576 0.980633020
1403638172995097088 -4.331479073 -6.913525581 8.233296394 0.062316582 0.137243196 0.123149298 0.980874717
1403638173045096960 -4.258580208 -6.860479355 8.149190903 0.057810687 0.135812104 0.124254942 0.981210291
1403638173095097088 -4.235233307 -6.868919373 8.170802116 0.051562041 0.135745019 0.128422618 0.981031239
1403638173145096960 -4.147069454 -6.818799973 8.084515572 0.045911804 0.134157956 0.128468528 0.981524110
1403638173195097088 -4.077657223 -6.751758099 8.007178307 0.042643014 0.134618074 0.127697930 0.981709123
1403638173245096960 -3.971776724 -6.688123703 7.928771019 0.039331988 0.134137049 0.123684943 0.982426763
1403638173295097088 -3.902554989 -6.642560482 7.816671371 0.034350637 0.136267975 0.119664080 0.982818186
1403638173345096960 -3.802782059 -6.527411938 7.771342278 0.033635311 0.137117714 0.113698892 0.983432710
1403638173395097088 -3.722535133 -6.469179630 7.677518368 0.031624451 0.141159162 0.106151931 0.983771145
1403638173445096960 -3.627280235 -6.400960445 7.593841553 0.027987832 0.144142583 0.097804651 0.984313905
1403638173495097088 -3.534391880 -6.311449528 7.492831707 0.024618227 0.146507755 0.091364279 0.984673560
1403638173545096960 -3.430274248 -6.254629135 7.383497238 0.021092189 0.147690460 0.086816818 0.984990060
1403638173595097088 -3.341910124 -6.157866001 7.270195961 0.020241043 0.150864333 0.080388755 0.985072553
1403638173645096960 -3.429391861 -6.243941784 7.478014946 0.016193159 0.160694331 0.085378692 0.983171225
1403638173695097088 -3.376761198 -6.183867931 7.414775372 0.014509605 0.164402246 0.084095694 0.982694924
1403638173745096960 -3.289793491 -6.089131355 7.343633652 0.015295616 0.164103091 0.085298918 0.982629299
1403638173795097088 -3.244168997 -6.057110786 7.275240421 0.011522979 0.166374415 0.086110182 0.982227981
1403638173845096960 -3.163504124 -5.973927021 7.202063560 0.010545627 0.167171702 0.087301813 0.981998384
1403638173895097088 -3.073123932 -5.882432938 7.120597839 0.009492038 0.167576909 0.084622808 0.982174516
1403638173945096960 -3.064115524 -5.849469185 7.068258286 0.009645292 0.171271503 0.087389693 0.981293082
1403638173995097088 -2.978324413 -5.779230118 6.979166031 0.008325774 0.171210542 0.087858647 0.981273949
1403638174045096960 -2.901377916 -5.690570831 6.885206699 0.006587293 0.171739712 0.087838188 0.981196523
1403638174095097088 -2.816570997 -5.608904839 6.769791603 0.008107756 0.171362534 0.088410929 0.981199622
1403638174145096960 -2.725886345 -5.529779911 6.677033424 0.005883474 0.170858622 0.087585144 0.981377363
1403638174195097088 -2.763893127 -5.581381798 6.646973610 -0.002824622 0.176049590 0.090823457 0.980178416
1403638174245096960 -2.687984943 -5.516348839 6.557982445 -0.007834529 0.176318824 0.089516513 0.980223000
1403638174295097088 -2.623805761 -5.426667213 6.464459896 -0.012394691 0.175995246 0.091025472 0.980095088
1403638174345096960 -2.569737196 -5.376443863 6.378189087 -0.016516654 0.176669642 0.090409584 0.979969978
1403638174395097088 -2.515621424 -5.296745300 6.293549538 -0.019448794 0.177010179 0.091314830 0.979770780
1403638174445096960 -2.434451103 -5.219148636 6.191650867 -0.023191720 0.176215664 0.090060748 0.979948580
1403638174495097088 -2.379402161 -5.148800850 6.113953114 -0.024805224 0.175744265 0.092377909 0.979777992
1403638174545096960 -2.301161528 -5.065989494 6.026102543 -0.027571175 0.174687386 0.093567498 0.979780197
1403638174595097088 -2.253670216 -5.009404659 5.941153526 -0.031782415 0.176969931 0.090039164 0.979573607
1403638174645096960 -2.171270847 -4.915707588 5.839528084 -0.035797674 0.177166089 0.088953696 0.979498863
1403638174695097088 -2.109438419 -4.871100426 5.773141861 -0.039748620 0.176736131 0.087632485 0.979543209
1403638174745096960 -2.050099850 -4.793790340 5.686564445 -0.042933665 0.177766621 0.087277912 0.979253948
1403638174795097088 -1.982386827 -4.740590572 5.595678806 -0.047247294 0.177779049 0.087348439 0.979046762
1403638174845096960 -1.912491322 -4.666220188 5.518156052 -0.048787318 0.177255169 0.086679988 0.979125619
1403638174895097088 -1.852246881 -4.607292175 5.442363739 -0.050131958 0.178605735 0.084855817 0.978972018
1403638174945096960 -1.786046743 -4.542740345 5.365961552 -0.051271096 0.179125562 0.084477246 0.978850782
1403638174995097088 -1.701513886 -4.481523991 5.274614334 -0.052702069 0.178924337 0.085040115 0.978762865
1403638175045096960 -1.626505733 -4.439037800 5.200938225 -0.051749859 0.179528221 0.084157579 0.978779376
1403638175095097088 -1.576978087 -4.376201630 5.127617359 -0.050944850 0.181110620 0.084771201 0.978477061
1403638175145096960 -1.502345443 -4.330163002 5.060506344 -0.050219312 0.181505054 0.083157353 0.978579998
1403638175195097088 -1.439184189 -4.302875519 4.992867470 -0.052191176 0.182850182 0.083389945 0.978206575
1403638175245096960 -1.366855621 -4.240080357 4.920345306 -0.052927971 0.185041055 0.081522621 0.977912307
1403638175295097088 -1.309233069 -4.200038433 4.851860046 -0.055453442 0.184687763 0.082717530 0.977738798
1403638175345096960 -1.248035669 -4.156486034 4.780246735 -0.059845570 0.185539067 0.083333299 0.977266252
1403638175395097088 -1.168557644 -4.110508442 4.715299129 -0.065250359 0.185725898 0.081347600 0.977052152
1403638175445096960 -1.119277477 -4.087609291 4.661005020 -0.071720026 0.188061878 0.079711154 0.976286352
1403638175495097088 -1.044525981 -4.040268421 4.587432861 -0.076543853 0.187257618 0.078868859 0.976143062
1403638175545096960 -0.989381075 -4.011620522 4.536970139 -0.084214136 0.188826472 0.076480635 0.975399017
1403638175595097088 -0.914373875 -4.006560326 4.488888264 -0.093236156 0.187536493 0.078835972 0.974639416
1403638175645096960 -0.851244628 -3.963845968 4.425998688 -0.098746814 0.186518505 0.080263264 0.974175394
1403638175695097088 -0.790695012 -3.947049618 4.382977486 -0.105769962 0.185811132 0.081494607 0.973470867
1403638175745096960 -0.733380377 -3.921872616 4.338337421 -0.108940743 0.185424834 0.082993843 0.973068118
1403638175795097088 -0.678469479 -3.912049770 4.301365376 -0.114035569 0.186240837 0.082784489 0.972346127
1403638175845096960 -0.594931483 -3.892454863 4.252244949 -0.116826139 0.183781520 0.082060210 0.972544134
1403638175895097088 -0.544442296 -3.864207506 4.230162144 -0.117538683 0.185151145 0.078959309 0.972455204
1403638175945096960 -0.467243969 -3.833400726 4.196544647 -0.117093526 0.184945092 0.075483158 0.972824097
1403638175995097088 -0.416231215 -3.817641497 4.172703266 -0.115152545 0.187157944 0.069290034 0.973093390
1403638176045096960 -0.326381624 -3.797163248 4.152043343 -0.108299248 0.185932621 0.066015184 0.974341989
1403638176095097088 -0.280475736 -3.779538393 4.140714645 -0.099371187 0.189423963 0.058825776 0.975081265
1403638176145096960 -0.230266690 -3.738134384 4.131960392 -0.084230326 0.191837445 0.053487077 0.976341546
1403638176195097088 -0.167026997 -3.740327358 4.133955002 -0.070162557 0.191642329 0.053568646 0.977486968
1403638176245096960 -0.100646019 -3.733283758 4.125647068 -0.057958987 0.190732762 0.057143085 0.978261948
1403638176295097088 -0.028208017 -3.708806992 4.114442825 -0.046692517 0.190015957 0.056183256 0.979059339
1403638176345096960 0.021988273 -3.695787907 4.112573147 -0.040767889 0.190692410 0.056524992 0.979172766
1403638176395097088 0.082593918 -3.695425034 4.111220360 -0.037712246 0.191455916 0.056420304 0.979152262
1403638176445096960 0.129639149 -3.695118427 4.103413582 -0.038189486 0.192372397 0.055858329 0.978986382
1403638176495097088 0.175103188 -3.685867310 4.105770588 -0.037495039 0.193491712 0.054599442 0.978863597
1403638176545096960 0.232222557 -3.674177170 4.103858948 -0.038052887 0.192872867 0.054829717 0.978951335
1403638176595097088 0.271013021 -3.679299831 4.103321075 -0.040392630 0.193577677 0.054687139 0.978726447
1403638176645096960 0.316211939 -3.662662029 4.102077484 -0.040536426 0.194296584 0.053765319 0.978629112
1403638176695097088 0.361803770 -3.668447495 4.103725433 -0.041498113 0.194530606 0.054246262 0.978515744
1403638176745096960 0.402408600 -3.664295197 4.108582497 -0.041267898 0.194599628 0.054367900 0.978504956
1403638176795097088 0.432868421 -3.670142889 4.109222889 -0.041775029 0.194856375 0.055674516 0.978358924
1403638176845096960 0.480156481 -3.669085026 4.100111485 -0.040235560 0.192712441 0.058581885 0.978678286
1403638176895097088 0.510545790 -3.674902916 4.102938652 -0.041058410 0.192691371 0.061203655 0.978487790
1403638176945096960 0.541642725 -3.681544065 4.113505363 -0.041156746 0.193134189 0.061300229 0.978390336
1403638176995097088 0.577489913 -3.679905415 4.106824875 -0.041297920 0.193219438 0.060079433 0.978443265
1403638177045096960 0.599526048 -3.691088438 4.115815639 -0.043368015 0.194542661 0.059120536 0.978149891
1403638177095097088 0.650792718 -3.694275856 4.110190392 -0.044116050 0.193428263 0.057540964 0.978431582
1403638177145096960 0.688530028 -3.690123796 4.120649815 -0.044254769 0.193920374 0.056129862 0.978409886
1403638177195097088 0.718309939 -3.692881584 4.131316662 -0.045418873 0.194549158 0.054606240 0.978317916
1403638177245096960 0.746217966 -3.704173088 4.135640621 -0.046267595 0.194859445 0.053428184 0.978281438
1403638177295097088 0.760683298 -3.692979336 4.156672955 -0.046042554 0.196000457 0.052790869 0.978098691
1403638177345096960 0.785298109 -3.695229530 4.165980339 -0.046153542 0.196119308 0.052097544 0.978106797
1403638177395097088 0.812905073 -3.688196659 4.175056458 -0.046017151 0.195820197 0.052296516 0.978162527
1403638177445096960 0.818714261 -3.680023670 4.189291000 -0.046605151 0.196237892 0.053957596 0.977960765
1403638177495097088 0.835250258 -3.675561905 4.204032421 -0.045717102 0.195504755 0.057814058 0.977929115
1403638177545096960 0.851864398 -3.672595739 4.221541405 -0.044261362 0.194023103 0.064213634 0.977891922
1403638177595097088 0.880456567 -3.655173779 4.250060081 -0.041967120 0.191252545 0.073776007 0.977864206
1403638177645096960 0.898929477 -3.647473335 4.267784595 -0.040350437 0.189907178 0.079069927 0.977780700
1403638177695097088 0.900484622 -3.641401529 4.279944420 -0.039197087 0.188885257 0.085767016 0.977460980
1403638177745096960 0.911903739 -3.636722565 4.304453850 -0.037261929 0.189109340 0.091775060 0.976947546
1403638177795097088 0.935797095 -3.630670547 4.317358971 -0.032844897 0.188296586 0.097796001 0.976678848
1403638177845096960 0.946723759 -3.634819269 4.341240883 -0.027616573 0.189367339 0.101579487 0.976247430
1403638177895097088 0.972490668 -3.613304853 4.360936165 -0.020373840 0.189507186 0.104172625 0.976125002
1403638177945096960 0.986742020 -3.615901709 4.382524490 -0.016137812 0.191103056 0.104943536 0.975810468
1403638177995097088 1.001022577 -3.606820345 4.405756474 -0.012094340 0.193058386 0.105026707 0.975475073
1403638178045096960 1.032902479 -3.594691277 4.412876606 -0.008440504 0.194665521 0.102982618 0.975412071
1403638178095097088 1.042049646 -3.587079048 4.434670448 -0.007172185 0.200566560 0.100342624 0.974501371
1403638178145096960 1.077309370 -3.585366726 4.456043720 -0.006495401 0.206126422 0.099863976 0.973394513
1403638178195097088 1.094884157 -3.586163282 4.457643509 -0.005179229 0.211885735 0.101665683 0.971978247
1403638178245096960 1.115872502 -3.580422878 4.466100693 -0.002362717 0.219399005 0.103851944 0.970089316
1403638178295097088 1.138152838 -3.587730646 4.468895912 -0.001922315 0.227956817 0.106843844 0.967789412
1403638178345096960 1.162430525 -3.589468718 4.471093178 -0.000359407 0.236997783 0.110625833 0.965191066
1403638178395097088 1.186740994 -3.590149641 4.472558022 0.000107406 0.247535795 0.114283480 0.962115049
1403638178445096960 1.211362720 -3.598960638 4.474036694 -0.001382735 0.257935494 0.119660929 0.958722353
1403638178495097088 1.229644656 -3.595157623 4.479365826 -0.004080575 0.269663990 0.124546319 0.954857528
1403638178545096960 1.245972872 -3.596832991 4.454722404 -0.007951203 0.279977441 0.132169887 0.950831532
1403638178595097088 1.264887929 -3.599103451 4.454415321 -0.012690693 0.291251034 0.138908118 0.946422935
1403638178645096960 1.283988476 -3.588418484 4.451848984 -0.014962156 0.301910400 0.145426810 0.942060113
1403638178695097088 1.301369905 -3.594115973 4.434447289 -0.017610291 0.312991261 0.151318550 0.937458813
1403638178745096960 1.325291276 -3.584323168 4.436618805 -0.017695481 0.323967785 0.155705214 0.932999253
1403638178795097088 1.353701115 -3.574976683 4.428110123 -0.019152626 0.334514439 0.160073400 0.928498685
1403638178845096960 1.379874587 -3.569775343 4.403771877 -0.022809401 0.343907952 0.163559288 0.924367607
1403638178895097088 1.399879575 -3.555780411 4.401820660 -0.025887117 0.352398962 0.167741656 0.920330107
1403638178945096960 1.424891233 -3.535212994 4.404489994 -0.029440541 0.360066384 0.170416281 0.916757166
1403638178995097088 1.451903939 -3.518870354 4.389180660 -0.034583732 0.364934027 0.173618048 0.914048076
1403638179045096960 1.483164310 -3.505353212 4.378463745 -0.040040426 0.369622320 0.175032765 0.911668599
1403638179095097088 1.506512880 -3.504420757 4.379944324 -0.046105128 0.374929547 0.172790319 0.909640372
1403638179145096960 1.525216937 -3.489531040 4.363431931 -0.050414652 0.380022258 0.172432497 0.907363474
1403638179195097088 1.564735293 -3.458992243 4.347870827 -0.052897330 0.383343220 0.173880234 0.905547082
1403638179245096960 1.586528063 -3.434607983 4.332812786 -0.056031335 0.388886392 0.173565552 0.903051972
1403638179295097088 1.620805383 -3.422066212 4.337723732 -0.060744923 0.394522130 0.173881143 0.900237620
1403638179345096960 1.652934313 -3.409734011 4.330236435 -0.064041831 0.401456803 0.173686564 0.896974981
1403638179395097088 1.695797205 -3.384539127 4.329454899 -0.062712595 0.408422887 0.173467934 0.893961251
1403638179445096960 1.715665936 -3.380485773 4.320703506 -0.057452902 0.417577595 0.176818579 0.889417410
1403638179495097088 1.764477491 -3.347936630 4.327114105 -0.049750090 0.426519424 0.178885654 0.885215282
1403638179545096960 1.788783431 -3.321382523 4.293949127 -0.042412795 0.435238391 0.182436794 0.880616546
1403638179595097088 1.830229878 -3.298555374 4.287338734 -0.038820602 0.444867820 0.184643179 0.875495553
1403638179645096960 1.857736707 -3.290750742 4.306552887 -0.037340086 0.456209421 0.187596515 0.869072080
1403638179695097088 1.902596474 -3.249779701 4.275276184 -0.032381341 0.465150744 0.190126464 0.863966525
1403638179745096960 1.949824691 -3.241864920 4.274891853 -0.032928318 0.475405276 0.193046838 0.857693672
1403638179795097088 1.979575753 -3.213518381 4.262191772 -0.030928388 0.485673547 0.195630237 0.851406753
1403638179845096960 2.029616117 -3.203045845 4.266915321 -0.030718450 0.497254610 0.197024435 0.844378829
1403638179895097088 2.066116810 -3.206672192 4.248751163 -0.032004368 0.505986989 0.203073367 0.837683737
1403638179945096960 2.102377415 -3.193671227 4.244615078 -0.034345407 0.513885617 0.207073465 0.831782758
1403638179995097088 2.138769627 -3.188065052 4.216244698 -0.038315993 0.519468486 0.212427929 0.826776087
1403638180045096960 2.172143459 -3.183372021 4.229753017 -0.043503240 0.525319457 0.216487080 0.821754336
1403638180095097088 2.214694500 -3.170848846 4.205949783 -0.043668065 0.529666841 0.221348941 0.817649543
1403638180145096960 2.254519939 -3.151816368 4.186504841 -0.043522723 0.532434285 0.223835051 0.815179288
1403638180195097088 2.296334267 -3.149988890 4.182618618 -0.044500902 0.536686957 0.224064901 0.812269509
1403638180245096960 2.336562395 -3.143511772 4.170147896 -0.045411728 0.539122701 0.225077093 0.810323894
1403638180295097088 2.372177601 -3.135907888 4.162546158 -0.046991836 0.540713549 0.226272747 0.808839500
1403638180345096960 2.419294834 -3.120593309 4.148839474 -0.047098853 0.541078627 0.227976233 0.808110416
1403638180395097088 2.469532967 -3.103729010 4.132520676 -0.048361048 0.541748583 0.227469474 0.807729721
1403638180445096960 2.507190704 -3.090814829 4.133110046 -0.050925497 0.542860448 0.226322904 0.807147503
1403638180495097088 2.555749893 -3.072726250 4.121727467 -0.051321246 0.543799937 0.223872051 0.807173550
1403638180545096960 2.597588539 -3.051749945 4.112611294 -0.052091114 0.544320464 0.221495584 0.807428896
1403638180595097088 2.644908667 -3.035733461 4.101443291 -0.053386629 0.544152379 0.220339060 0.807774007
1403638180645096960 2.687868834 -3.019525766 4.092947006 -0.055979587 0.543717027 0.219516963 0.808115363
1403638180695097088 2.732754946 -3.008597374 4.084147453 -0.058511343 0.542839527 0.219367817 0.808566332
1403638180745096960 2.780516624 -2.990753174 4.071160316 -0.062784269 0.540970683 0.219742224 0.809396207
1403638180795097088 2.834025145 -2.981846333 4.065092087 -0.064444393 0.539345682 0.221446484 0.809885561
1403638180845096960 2.882953167 -2.974282742 4.057844639 -0.065722167 0.537755787 0.221773595 0.810750127
1403638180895097088 2.936300993 -2.962366104 4.045534134 -0.064369500 0.535799265 0.222613737 0.811922967
1403638180945096960 2.994840145 -2.958152294 4.040133953 -0.063981205 0.534411132 0.222909480 0.812786877
1403638180995097088 3.052737236 -2.945192099 4.029406548 -0.061097756 0.532914579 0.223893672 0.813720345
1403638181045096960 3.102096558 -2.937114716 4.024971485 -0.058695737 0.531806052 0.223656595 0.814686954
1403638181095097088 3.163964272 -2.926281214 4.019906044 -0.057731338 0.530632675 0.223767906 0.815490067
1403638181145096960 3.217194080 -2.917423248 4.012348652 -0.055061657 0.529194713 0.225680962 0.816081643
1403638181195097088 3.274792671 -2.903501987 4.013424397 -0.051545192 0.529074073 0.224457279 0.816726804
1403638181245096960 3.335969925 -2.890262365 4.003370285 -0.046123598 0.528765798 0.224655226 0.817196071
1403638181295097088 3.394366503 -2.879228592 4.000788689 -0.038808472 0.530434847 0.225745022 0.816193581
1403638181345096960 3.453435898 -2.862885952 3.996513844 -0.033255015 0.533817887 0.226210907 0.814101458
1403638181395097088 3.514751911 -2.848888397 3.992003441 -0.027793514 0.538101912 0.228755608 0.810768008
1403638181445096960 3.579973936 -2.827511787 3.987902880 -0.022579091 0.543533087 0.232967421 0.806094408
1403638181495097088 3.644397497 -2.804217339 3.973227978 -0.015115122 0.550506353 0.236216471 0.800572336
1403638181545096960 3.697298527 -2.788214207 3.966630936 -0.005131423 0.559602141 0.237397492 0.794016063
1403638181595097088 3.756299257 -2.769670486 3.956595421 0.001150152 0.569919765 0.235763624 0.787150323
1403638181645096960 3.827952862 -2.742468596 3.936523438 0.003891590 0.579536676 0.236022845 0.780009806
1403638181695097088 3.883939028 -2.726597309 3.920988560 0.000890451 0.589804530 0.235145599 0.772551835
1403638181745096960 3.934835434 -2.708857536 3.898882866 -0.002988496 0.599171996 0.236388028 0.764921367
1403638181795097088 3.988111973 -2.694968224 3.875902653 -0.007837950 0.609260798 0.236104235 0.756964087
1403638181845096960 4.045667171 -2.676884651 3.848643064 -0.013811237 0.618352652 0.237022996 0.749179125
1403638181895097088 4.112490177 -2.653485060 3.820629358 -0.019941909 0.627386034 0.238149032 0.741130292
1403638181945096960 4.159467697 -2.642825127 3.792909145 -0.024957430 0.634331405 0.240965560 0.734122872
1403638181995097088 4.219590664 -2.630557299 3.766429186 -0.029229520 0.640348613 0.244483992 0.727548540
1403638182045096960 4.273399353 -2.618343830 3.738806963 -0.033178296 0.644377053 0.249658480 0.722044349
1403638182095097088 4.323765278 -2.612458706 3.707808018 -0.036361594 0.648088098 0.253277272 0.717293680
1403638182145096960 4.382460594 -2.602238178 3.679626226 -0.039616864 0.650887489 0.256837040 0.713309646
1403638182195097088 4.433534622 -2.597466469 3.647843122 -0.041186862 0.653134108 0.260165185 0.709953189
1403638182245096960 4.484649658 -2.592242718 3.622230530 -0.041660979 0.654167593 0.265682131 0.706924379
1403638182295097088 4.542844772 -2.578432560 3.589080095 -0.041272957 0.654358327 0.270304710 0.705015600
1403638182345096960 4.589088917 -2.574877977 3.557352543 -0.040193435 0.654323041 0.274222910 0.703596175
1403638182395097088 4.642666817 -2.565562248 3.528179884 -0.040981282 0.653505862 0.278133243 0.702774823
1403638182445096960 4.701448441 -2.553864956 3.496328592 -0.044253957 0.654503405 0.276863337 0.702149332
1403638182495097088 4.753931522 -2.552481890 3.461931944 -0.049398165 0.654561460 0.275620192 0.702241182
1403638182545096960 4.812015533 -2.541087866 3.422421932 -0.054547995 0.655117095 0.272023648 0.702744067
1403638182595097088 4.872656822 -2.536734104 3.389563084 -0.060326885 0.655704439 0.268108487 0.703228474
1403638182645096960 4.931758881 -2.534008980 3.353250742 -0.063041501 0.655334592 0.266444653 0.703967035
1403638182695097088 4.992795467 -2.535796165 3.320139647 -0.065138787 0.654549003 0.264990926 0.705054820
1403638182745096960 5.055751801 -2.534647703 3.281348228 -0.063929722 0.653537750 0.265176594 0.706033051
1403638182795097088 5.120662689 -2.536550999 3.247060776 -0.063445687 0.652978301 0.264327139 0.706912398
1403638182845096960 5.184069633 -2.532809496 3.209481716 -0.061611973 0.652306557 0.263508171 0.707999706
1403638182895097088 5.253402710 -2.532044649 3.175593853 -0.059494268 0.651964664 0.261736482 0.709151983
1403638182945096960 5.319960117 -2.525211811 3.142544746 -0.055794459 0.651732981 0.260449827 0.710138738
1403638182995097088 5.372905731 -2.536041737 3.116969824 -0.052620087 0.652464926 0.256721020 0.711066127
1403638183045096960 5.444005013 -2.525390625 3.083982706 -0.048883192 0.653017461 0.253517270 0.711974442
1403638183095097088 5.521793365 -2.509702444 3.051157951 -0.046737168 0.653834760 0.249081492 0.712933481
1403638183145096960 5.576414585 -2.514664650 3.017510653 -0.047147851 0.654580355 0.244256362 0.713891089
1403638183195097088 5.650145054 -2.507488966 2.994976759 -0.047188893 0.655317128 0.242153406 0.713928819
1403638183245096960 5.704861164 -2.494533777 2.955348015 -0.050297704 0.654533684 0.240762964 0.714904845
1403638183295097088 5.780169010 -2.473187685 2.932284117 -0.053413421 0.653878093 0.241807804 0.714926124
1403638183345096960 5.860613823 -2.461944580 2.897085190 -0.057214241 0.652059793 0.245550394 0.715017140
1403638183395097088 5.932946205 -2.442852974 2.872011423 -0.060313590 0.650418401 0.249005303 0.715062618
1403638183445096960 5.999154568 -2.430128098 2.846461773 -0.065491147 0.649505138 0.251035362 0.714727342
1403638183495097088 6.063536644 -2.422019958 2.822834253 -0.069721229 0.648786724 0.252111673 0.714600861
1403638183545096960 6.126966953 -2.404538870 2.800779819 -0.073018469 0.648486555 0.252566040 0.714383602
1403638183595097088 6.203505039 -2.382092714 2.782194138 -0.073485009 0.648063421 0.253643990 0.714337766
1403638183645096960 6.269558907 -2.372840166 2.758171082 -0.071420275 0.648585081 0.252182662 0.714591086
1403638183695097088 6.337926865 -2.359227896 2.734753132 -0.068490557 0.650323987 0.247085392 0.715077996
1403638183745096960 6.418771744 -2.345994711 2.713359833 -0.062434081 0.652134418 0.243112683 0.715345323
1403638183795097088 6.495409966 -2.332768917 2.691306829 -0.059339248 0.653936863 0.237481162 0.715854824
1403638183845096960 6.570358753 -2.324393034 2.672086716 -0.055497762 0.655837297 0.231355309 0.716430128
1403638183895097088 6.633232117 -2.335395098 2.651300907 -0.052551989 0.657218695 0.228969499 0.716152787
1403638183945096960 6.710491657 -2.327763081 2.632744551 -0.051158857 0.657708645 0.227667063 0.716219127
1403638183995097088 6.786162853 -2.322371960 2.613063335 -0.051295940 0.657741070 0.228025109 0.716065586
1403638184045096960 6.852367401 -2.322516918 2.598634720 -0.051941209 0.657288730 0.230048165 0.715787292
1403638184095097088 6.941246986 -2.330115557 2.586479425 -0.055279661 0.656587481 0.233667970 0.715007961
1403638184145096960 7.012482166 -2.331725121 2.571380854 -0.059788421 0.655459225 0.236874312 0.714625120
1403638184195097088 7.083630562 -2.333885670 2.556800842 -0.062500432 0.654003799 0.241999194 0.714009225
1403638184245096960 7.151638508 -2.337679148 2.545179367 -0.065428741 0.653337061 0.245019332 0.713326991
1403638184295097088 7.221052170 -2.333449125 2.531781673 -0.065313987 0.653094590 0.246515900 0.713043809
1403638184345096960 7.280740738 -2.343804836 2.522703409 -0.066072948 0.653863549 0.244646460 0.712912977
1403638184395097088 7.378834724 -2.335821867 2.514058590 -0.063008629 0.654811442 0.242988452 0.712887466
1403638184445096960 7.454200745 -2.330647469 2.500995159 -0.060489342 0.655754387 0.241094142 0.712882042
1403638184495097088 7.520040512 -2.332114697 2.499533176 -0.060325172 0.656913042 0.237565786 0.713013768
1403638184545096960 7.595478535 -2.327767134 2.490358353 -0.058001559 0.657269061 0.237696409 0.712834954
1403638184595097088 7.658492565 -2.326800823 2.483681202 -0.057105206 0.657863557 0.236737877 0.712677836
1403638184645096960 7.731550217 -2.324572802 2.481967688 -0.055022378 0.658225000 0.235864177 0.712797582
1403638184695097088 7.803661346 -2.322662115 2.476387739 -0.056153193 0.658562303 0.235466450 0.712529302
1403638184745096960 7.877616405 -2.324665070 2.478439808 -0.054851830 0.658488512 0.236830324 0.712246835
1403638184795097088 7.955980301 -2.321196795 2.474624872 -0.054138411 0.658514798 0.236466691 0.712397814
1403638184845096960 8.027008057 -2.324469328 2.470751524 -0.054834403 0.658618033 0.237428561 0.711929083
1403638184895097088 8.093337059 -2.321128368 2.471063137 -0.055500165 0.659385622 0.235682249 0.711747229
1403638184945096960 8.166859627 -2.317479610 2.470692873 -0.053522859 0.660028338 0.234631971 0.711649954
1403638184995097088 8.235101700 -2.319441080 2.463618279 -0.052589126 0.659737885 0.235320166 0.711761653
1403638185045096960 8.304638863 -2.316926718 2.467204571 -0.052003451 0.659596622 0.235670581 0.711819708
1403638185095097088 8.378528595 -2.326007843 2.469279766 -0.054821067 0.659819007 0.235234857 0.711546242
1403638185145096960 8.450868607 -2.325938940 2.474278927 -0.056207702 0.659577191 0.235217720 0.711667955
1403638185195097088 8.518335342 -2.330945730 2.477822304 -0.057149217 0.659938395 0.233757094 0.711739361
1403638185245096960 8.603492737 -2.332481623 2.488258123 -0.060105868 0.660515487 0.231459811 0.711711228
1403638185295097088 8.667471886 -2.337807178 2.491990089 -0.060756724 0.660831809 0.229739353 0.711919844
1403638185345096960 8.749084473 -2.327141047 2.507080555 -0.061519194 0.661376297 0.227616444 0.712030649
1403638185395097088 8.810792923 -2.344392776 2.505402565 -0.061815992 0.661454797 0.224229574 0.713005900
1403638185445096960 8.868465424 -2.350943565 2.515909433 -0.061450910 0.660643876 0.219737068 0.715184629
1403638185495097088 8.930223465 -2.345972061 2.527696371 -0.059870083 0.658756614 0.215017200 0.718486547
1403638185545096960 9.009735107 -2.356909990 2.535949707 -0.059836365 0.654692352 0.210368261 0.723562539
1403638185595097088 9.087326050 -2.366981506 2.545107603 -0.058133733 0.650280833 0.207299680 0.728547931
1403638185645096960 9.140671730 -2.376243114 2.554479599 -0.057669319 0.646183372 0.203455716 0.733298779
1403638185695097088 9.205062866 -2.378791094 2.579230070 -0.053910322 0.641980410 0.202620938 0.737495482
1403638185745096960 9.262886047 -2.392123938 2.604683876 -0.050179362 0.637962043 0.202770740 0.741195321
1403638185795097088 9.324962616 -2.406815529 2.614636183 -0.046526555 0.632121444 0.208340839 0.744883835
1403638185845096960 9.394497871 -2.417320490 2.641281605 -0.040719714 0.625969231 0.218792632 0.747418404
1403638185895097088 9.443582535 -2.425985813 2.661516190 -0.036175318 0.620105147 0.228178218 0.749730349
1403638185945096960 9.510472298 -2.428149939 2.678995609 -0.032240503 0.614669859 0.237514406 0.751484156
1403638185995097088 9.587688446 -2.439501286 2.697373152 -0.030599756 0.610972345 0.241879940 0.753173590
1403638186045096960 9.644195557 -2.435561895 2.719494343 -0.032822799 0.610032141 0.241140977 0.754078567
1403638186095097088 9.703292847 -2.449779034 2.729654312 -0.037442632 0.609363079 0.239443824 0.754944563
1403638186145096960 9.756683350 -2.455638170 2.739873409 -0.040556341 0.609662235 0.236226961 0.755555332
1403638186195097088 9.830430031 -2.425573587 2.754861832 -0.043215130 0.609954357 0.232723430 0.756259143
1403638186245096960 9.882663727 -2.435490608 2.764368773 -0.044618826 0.609909236 0.232293591 0.756346166
1403638186295097088 9.947509766 -2.433711767 2.789655209 -0.046667226 0.610627830 0.229402527 0.756525040
1403638186345096960 9.996878624 -2.430956602 2.799342394 -0.048100464 0.610729098 0.228488699 0.756630123
1403638186395097088 10.051881790 -2.441719532 2.814870834 -0.049225524 0.610703170 0.227960244 0.756738186
1403638186445096960 10.109905243 -2.456963539 2.841804028 -0.049298566 0.611455321 0.227584630 0.756238878
1403638186495097088 10.156364441 -2.466822147 2.853204966 -0.048816830 0.612188935 0.226365745 0.756042421
1403638186545096960 10.232069969 -2.480335712 2.866538286 -0.050579913 0.612901628 0.225205034 0.755695641
1403638186595097088 10.291942596 -2.484993219 2.880525589 -0.051826466 0.613754034 0.223678231 0.755372763
1403638186645096960 10.344474792 -2.492786884 2.901865482 -0.053392224 0.614584684 0.222750083 0.754862487
1403638186695097088 10.403141022 -2.514933348 2.916203022 -0.056453720 0.615746200 0.219878063 0.754535019
1403638186745096960 10.462690353 -2.513481855 2.927637815 -0.058063559 0.615915418 0.216321900 0.755302370
1403638186795097088 10.530617714 -2.501168728 2.949740410 -0.059881039 0.615197361 0.211901650 0.756996751
1403638186845096960 10.570284843 -2.507552385 2.968707561 -0.061803069 0.613715112 0.207576618 0.759240448
1403638186895097088 10.626286507 -2.496352196 2.996610880 -0.064679816 0.610383093 0.203794107 0.762703717
1403638186945096960 10.700628281 -2.513087511 3.030183554 -0.065372251 0.605268419 0.201948300 0.767198443
1403638186995097088 10.753479004 -2.518741131 3.067031860 -0.065754987 0.598777771 0.200538695 0.772609651
1403638187045096960 10.815369606 -2.546752214 3.100560904 -0.062378127 0.590200007 0.199402779 0.779750884
1403638187095097088 10.842864037 -2.552449942 3.139845848 -0.056048915 0.580781162 0.198567867 0.787478626
1403638187145096960 10.911894798 -2.517894030 3.141698599 -0.047590788 0.569265425 0.195821688 0.797073364
1403638187195097088 10.930730820 -2.573418379 3.160559893 -0.042745452 0.557785094 0.194192410 0.805815041
1403638187245096960 11.018418312 -2.615353346 3.201043606 -0.037577018 0.546338439 0.190066174 0.814847887
1403638187295097088 11.107639313 -2.592231512 3.222861528 -0.029563973 0.534928560 0.184634537 0.823946297
1403638187345096960 11.160006523 -2.583997011 3.232365608 -0.024830036 0.523787856 0.179158702 0.832425356
1403638187395097088 11.163974762 -2.657023191 3.286319256 -0.021852391 0.516092718 0.173709631 0.838448405
1403638187445096960 11.195808411 -2.665750742 3.311920404 -0.017776810 0.508119345 0.169938058 0.844168127
1403638187495097088 11.252658844 -2.684342861 3.330810785 -0.016639965 0.500831366 0.166357830 0.849244475
1403638187545096960 11.321018219 -2.730872154 3.365655422 -0.017935758 0.494531870 0.167167082 0.852743626
1403638187595097088 11.367245674 -2.704939842 3.399166346 -0.019975493 0.489045382 0.166288659 0.856027901
1403638187645096960 11.405763626 -2.757357359 3.410043716 -0.024764327 0.484417170 0.168524444 0.858094573
1403638187695097088 11.415775299 -2.801352739 3.447478771 -0.030125638 0.482549071 0.168269411 0.859025180
1403638187745096960 11.510709763 -2.747850418 3.476553679 -0.028673263 0.479936391 0.167333260 0.860719740
1403638187795097088 11.524444580 -2.803252697 3.488269567 -0.034225103 0.479152679 0.165067807 0.861390710
1403638187845096960 11.608440399 -2.835078478 3.538609743 -0.034840986 0.479512185 0.163232267 0.861515760
1403638187895097088 11.632947922 -2.855307817 3.566582203 -0.037442237 0.480672151 0.158879668 0.861573875
1403638187945096960 11.679430962 -2.867014170 3.595118046 -0.036377825 0.481873542 0.155874625 0.861497343
1403638187995097088 11.727806091 -2.867289782 3.618924618 -0.035241053 0.483716726 0.150637373 0.861443281
1403638188045096960 11.764844894 -2.877637863 3.653276205 -0.033686299 0.486133844 0.146423444 0.860871196
1403638188095097088 11.767895699 -2.899993420 3.672719240 -0.035151221 0.488777459 0.140999198 0.860221028
1403638188145096960 11.792783737 -2.910196066 3.710162163 -0.033648439 0.491492331 0.137395829 0.859316826
1403638188195097088 11.845501900 -2.914917946 3.739206314 -0.029876381 0.492619842 0.135014698 0.859188020
1403638188245096960 11.853634834 -2.917350292 3.739905357 -0.023655804 0.493168265 0.134677827 0.859120071
1403638188295097088 11.876226425 -2.964472294 3.789008856 -0.013733687 0.494474798 0.136310950 0.858327091
1403638188345096960 11.914456367 -2.958900452 3.812854528 -0.002338776 0.494182736 0.136813521 0.858521998
1403638188395097088 11.925519943 -2.985024929 3.866337538 0.007468425 0.495546132 0.136187583 0.857806027
1403638188445096960 11.961739540 -2.980334282 3.914775133 0.016201776 0.496137321 0.136321276 0.857322454
1403638188495097088 11.963848114 -2.982158661 3.948051453 0.023432503 0.496213049 0.137580097 0.856910288
1403638188545096960 11.958498001 -2.997500896 3.958142757 0.030858694 0.496505082 0.139196247 0.856244564
1403638188595097088 11.955800056 -3.031941891 4.006051064 0.032011818 0.495941341 0.139914259 0.856411934
1403638188645096960 11.986960411 -2.982208252 4.020908833 0.033182517 0.493364364 0.139187112 0.857972860
1403638188695097088 11.967670441 -3.009173870 4.038413048 0.030757636 0.490211993 0.140759557 0.859612107
1403638188745096960 11.958482742 -3.034952879 4.065823555 0.026276588 0.485509306 0.142693967 0.862107098
1403638188795097088 11.943167686 -3.055302143 4.100786209 0.019085877 0.482395023 0.143512294 0.863906860
1403638188845096960 11.901700974 -3.052853584 4.113654613 0.015301176 0.478760123 0.144638732 0.865814209
1403638188895097088 11.874879837 -3.099161148 4.117300034 0.010853383 0.474693805 0.146362573 0.867828310
1403638188945096960 11.842537880 -3.134751797 4.133037567 0.006497840 0.472045660 0.147743568 0.869081438
1403638188995097088 11.835605621 -3.133195877 4.126175880 0.005559035 0.468001813 0.149003118 0.871057689
1403638189045096960 11.795993805 -3.150767803 4.163485527 0.003089292 0.465146005 0.148183748 0.872737825
1403638189095097088 11.775925636 -3.188134670 4.162964821 0.003702406 0.459659964 0.149469301 0.875418723
1403638189145096960 11.771280289 -3.185204268 4.180968285 0.003546128 0.453903437 0.147471562 0.878755510
1403638189195097088 11.727156639 -3.204498291 4.174433231 0.004882908 0.446273297 0.148583040 0.882462144
1403638189245096960 11.707917213 -3.217745781 4.192928791 0.004882429 0.438033015 0.149046838 0.886503398
1403638189295097088 11.639891624 -3.268506050 4.183425903 0.000065518 0.428818107 0.147165388 0.891323388
1403638189345096960 11.563217163 -3.280802965 4.150591850 -0.003815010 0.418449730 0.147683784 0.896144390
1403638189395097088 11.564941406 -3.266154766 4.188217163 -0.011445625 0.410494387 0.147063687 0.899853110
1403638189445096960 11.526741028 -3.290684700 4.189784527 -0.020546891 0.401779026 0.148182347 0.903434277
1403638189495097088 11.492386818 -3.311665297 4.183502674 -0.028001582 0.394061506 0.149806917 0.906360507
1403638189545096960 11.464766502 -3.307238817 4.175553322 -0.032193355 0.386918515 0.151049197 0.909088433
1403638189595097088 11.417640686 -3.321900368 4.231919289 -0.035704117 0.384120345 0.151254267 0.910109282
1403638189645096960 11.394375801 -3.322062016 4.214978695 -0.037853852 0.378655523 0.152168676 0.912157774
1403638189695097088 11.376681328 -3.325675964 4.201893806 -0.041808780 0.373410672 0.154362112 0.913777173
1403638189745096960 11.354982376 -3.344717741 4.217142105 -0.045403745 0.370212466 0.158197090 0.914251029
1403638189795097088 11.289579391 -3.370017529 4.242471695 -0.049839396 0.369240224 0.159985870 0.914101839
1403638189845096960 11.236671448 -3.388258696 4.256109238 -0.054183755 0.368466794 0.161412776 0.913915932
1403638189895097088 11.235149384 -3.393866301 4.258606911 -0.057987858 0.366304457 0.162564278 0.914347470
1403638189945096960 11.174145699 -3.435218096 4.252220154 -0.062654056 0.366138071 0.163388684 0.913959265
1403638189995097088 11.165824890 -3.414510965 4.252202988 -0.061143633 0.365826190 0.161575630 0.914508581
1403638190045096960 11.156355858 -3.420885324 4.259104729 -0.056826029 0.366627872 0.160079092 0.914729178
1403638190095097088 11.118825912 -3.444920063 4.283266544 -0.052482210 0.368708253 0.157477722 0.914604068
1403638190145096960 11.080318451 -3.481808424 4.300037384 -0.047071010 0.371365786 0.154721320 0.914293766
1403638190195097088 11.045572281 -3.470753908 4.309714317 -0.040310208 0.373690367 0.149853170 0.914480507
1403638190245096960 11.035037994 -3.453571558 4.306862831 -0.033010550 0.375571251 0.142845690 0.915123820
1403638190295097088 11.014416695 -3.451848030 4.312092304 -0.028348835 0.377804369 0.132672340 0.915892065
1403638190345096960 10.982093811 -3.472588778 4.337616920 -0.025639394 0.379190624 0.122907691 0.916761041
1403638190395097088 10.979900360 -3.417150736 4.348107815 -0.020653013 0.377874017 0.111535966 0.918882132
1403638190445096960 10.938747406 -3.447611809 4.349264145 -0.022093162 0.376355857 0.103581063 0.920401633
1403638190495097088 10.931912422 -3.438951015 4.355987549 -0.021183291 0.373171568 0.099650152 0.922151923
1403638190545096960 10.886203766 -3.444081306 4.393105507 -0.022379417 0.370224357 0.098266400 0.923459172
1403638190595097088 10.868312836 -3.408939838 4.416352272 -0.022092942 0.366410553 0.098480560 0.924963117
1403638190645096960 10.810472488 -3.416551590 4.454571724 -0.022821307 0.364144742 0.098887883 0.925796449
1403638190695097088 10.791929245 -3.466479301 4.466170311 -0.024382534 0.360251963 0.102006763 0.926940501
1403638190745096960 10.748971939 -3.473920107 4.488523960 -0.024119731 0.357949495 0.102135353 0.927824736
1403638190795097088 10.722040176 -3.485548735 4.493863106 -0.022723308 0.353858948 0.107274868 0.928848505
1403638190845096960 10.675827026 -3.463640928 4.508165359 -0.020481331 0.350085884 0.112645529 0.929694235
1403638190895097088 10.658348083 -3.479261875 4.499520302 -0.020259995 0.345728964 0.117225036 0.930762768
1403638190945096960 10.584918022 -3.501684189 4.529340744 -0.021583140 0.345328003 0.119304441 0.930617630
1403638190995097088 10.539012909 -3.511734247 4.504631519 -0.020130038 0.342322618 0.121461645 0.931481123
1403638191045096960 10.502490997 -3.515050888 4.507313728 -0.016127577 0.341097206 0.121301889 0.932029188
1403638191095097088 10.433681488 -3.578440666 4.534724712 -0.015384863 0.342435479 0.122114398 0.931444764
1403638191145096960 10.418769836 -3.520655394 4.574494362 -0.013364987 0.341482401 0.122605972 0.931761205
1403638191195097088 10.369380951 -3.512396812 4.581291199 -0.016671803 0.340260923 0.124513902 0.931901753
1403638191245096960 10.330892563 -3.537951946 4.584928513 -0.023677738 0.339092672 0.126704097 0.931880653
1403638191295097088 10.270420074 -3.545931101 4.608815193 -0.028574158 0.338851899 0.130804107 0.931264281
1403638191345096960 10.249988556 -3.585617065 4.616648197 -0.034446392 0.338127077 0.130909503 0.931314230
1403638191395097088 10.192422867 -3.554813862 4.634346008 -0.035613891 0.338626742 0.131544307 0.930999279
1403638191445096960 10.129102707 -3.590353966 4.646129608 -0.037407000 0.339126289 0.133491993 0.930469751
1403638191495097088 10.099407196 -3.624722004 4.645790100 -0.038650405 0.338839501 0.134569570 0.930368185
1403638191545096960 10.066011429 -3.663641453 4.653442383 -0.041602779 0.339520723 0.133407295 0.930159867
1403638191595097088 10.031634331 -3.621240616 4.696592331 -0.040323496 0.340852022 0.131006837 0.930070460
1403638191645096960 10.006595612 -3.617047310 4.700062275 -0.039611939 0.341017574 0.130449593 0.930118680
1403638191695097088 9.926486969 -3.693775654 4.696213722 -0.043475512 0.342191041 0.128408790 0.929799080
1403638191745096960 9.911602974 -3.659499645 4.717280388 -0.043960266 0.343411237 0.124565504 0.929849267
1403638191795097088 9.865123749 -3.697477341 4.748501301 -0.046457730 0.345308632 0.121754706 0.929397345
1403638191845096960 9.821814537 -3.680981159 4.758666992 -0.046566758 0.345675141 0.120778210 0.929383039
1403638191895097088 9.785617828 -3.706100941 4.800535202 -0.047037933 0.346461356 0.119762689 0.929197967
1403638191945096960 9.752037048 -3.700856924 4.792333603 -0.046660993 0.345863283 0.120370150 0.929361284
1403638191995097088 9.702526093 -3.707549095 4.811397076 -0.046108589 0.345499635 0.120906770 0.929454446
1403638192045096960 9.582538605 -3.776088238 4.813799858 -0.048457965 0.347012728 0.119747616 0.928921163
1403638192095097088 9.603370667 -3.709329128 4.897367477 -0.045772482 0.346768975 0.118287750 0.929335356
1403638192145096960 9.559867859 -3.729961395 4.892044067 -0.044343535 0.345443010 0.120212831 0.929651380
1403638192195097088 9.532111168 -3.772202492 4.916995525 -0.043525219 0.345251381 0.121089056 0.929647505
1403638192245096960 9.462495804 -3.773578167 4.956162930 -0.039567433 0.345746398 0.121065482 0.929643452
1403638192295097088 9.469149590 -3.782463789 4.928876877 -0.034134604 0.343253076 0.122062325 0.930651903
1403638192345096960 9.428165436 -3.804384470 4.978562832 -0.028374026 0.343844473 0.122529082 0.930565715
1403638192395097088 9.368085861 -3.822413445 5.024858475 -0.024776563 0.344731510 0.122504108 0.930343509
1403638192445096960 9.348439217 -3.823314667 4.994776726 -0.023255454 0.342787743 0.121774517 0.931196392
1403638192495097088 9.280370712 -3.871641159 5.011678696 -0.020101890 0.343001038 0.123410031 0.930975914
1403638192545096960 9.242256165 -3.907815456 5.044257164 -0.019433003 0.343584120 0.121299431 0.931052506
1403638192595097088 9.236133575 -3.931016684 5.081566811 -0.014832641 0.343519837 0.120051265 0.931322634
1403638192645096960 9.209033966 -3.971380711 5.036864281 -0.008963298 0.342636853 0.117720261 0.932020187
1403638192695097088 9.109724045 -3.979292393 5.107770920 -0.001888193 0.345440686 0.118953459 0.930869102
1403638192745096960 9.039490700 -4.025059700 5.145336151 0.002561780 0.347251296 0.116918057 0.930451572
1403638192795097088 8.999029160 -4.024378300 5.180452347 0.009482666 0.346848160 0.117172755 0.930525064
1403638192845096960 8.961828232 -4.039809704 5.198313713 0.015372723 0.346582890 0.117573649 0.930494666
1403638192895097088 8.926246643 -4.007090569 5.152504444 0.026055478 0.343763739 0.119648516 0.931038022
1403638192945096960 8.916847229 -4.054604053 5.161734581 0.035846591 0.340988636 0.123389907 0.931244671
1403638192995097088 8.861387253 -4.055776596 5.208527565 0.047275621 0.340540379 0.126421258 0.930491745
1403638193045096960 8.817481995 -4.002481461 5.213949680 0.055979501 0.336915553 0.129152149 0.930953205
1403638193095097088 8.804088593 -4.047551155 5.220727921 0.054990754 0.332490444 0.130855516 0.932364166
1403638193145096960 8.692333221 -4.093247414 5.217671871 0.048289932 0.329526216 0.129987359 0.933907807
1403638193195097088 8.652122498 -4.089414597 5.182901859 0.042066932 0.324605614 0.127356663 0.936291516
1403638193245096960 8.598144531 -4.097268105 5.160121918 0.036033735 0.320803612 0.124847978 0.938189566
1403638193295097088 8.581226349 -4.064945221 5.077390671 0.032481726 0.313803196 0.122761324 0.940958142
1403638193345096960 8.579992294 -4.109369755 5.022246361 0.024840599 0.308583796 0.117786586 0.943549335
1403638193395097088 8.518529892 -4.126307487 4.992855072 0.022590086 0.307116926 0.112652637 0.944710672
1403638193445096960 8.491581917 -4.123986244 4.918445587 0.022154633 0.304372638 0.109732233 0.945952058
1403638193495097088 8.461645126 -4.159843922 4.914557457 0.022641504 0.302544117 0.106977284 0.946842253
1403638193545096960 8.424461365 -4.149743080 4.809351921 0.024086624 0.298652679 0.104509428 0.948316514
1403638193595097088 8.336228371 -4.212807655 4.723076820 0.020678451 0.296287328 0.105850749 0.948989928
1403638193645096960 8.252192497 -4.236233711 4.760121822 0.016185733 0.297538906 0.105731927 0.948698819
1403638193695097088 8.209024429 -4.203989029 4.723894119 0.011696868 0.294209868 0.108936585 0.949440122
1403638193745096960 8.157600403 -4.249175549 4.679134369 0.003379998 0.291532040 0.111665756 0.950014949
1403638193795097088 8.096506119 -4.239664555 4.632419586 -0.001039718 0.289970875 0.113684438 0.950258732
1403638193845096960 8.012695312 -4.306451321 4.622339725 -0.008116201 0.290425479 0.113998294 0.950048208
1403638193895097088 7.954531670 -4.301607132 4.606673241 -0.010753537 0.291097343 0.114703275 0.949731469
1403638193945096960 7.908567429 -4.335959911 4.599445820 -0.015030805 0.290685326 0.116701216 0.949556231
1403638193995097088 7.826854706 -4.335158825 4.609770775 -0.015927410 0.291761398 0.117360279 0.949130237
1403638194045096960 7.813076019 -4.320069313 4.532695770 -0.014251760 0.288882524 0.118271075 0.949924111
1403638194095097088 7.764752865 -4.322392941 4.463603973 -0.011836669 0.289849490 0.116739541 0.949852169
1403638194145096960 7.648340702 -4.350889206 4.476995945 -0.007895547 0.291883498 0.115938462 0.949368179
1403638194195097088 7.605245590 -4.269423485 4.446705341 0.001081078 0.291758090 0.114529416 0.949609995
1403638194245096960 7.582948685 -4.305351734 4.373238564 0.001615670 0.291281760 0.112878643 0.949953020
1403638194295097088 7.580474377 -4.342765331 4.273002148 0.001029371 0.287525207 0.113013625 0.951081574
1403638194345096960 7.410139561 -4.367764473 4.331085205 -0.002791516 0.292031944 0.114301935 0.949549675
1403638194395097088 7.346915245 -4.338856697 4.319725037 -0.004450803 0.291873485 0.115300760 0.949471295
1403638194445096960 7.287706375 -4.314648628 4.271634102 -0.006879060 0.290928751 0.117626429 0.949461520
1403638194495097088 7.239326477 -4.316121101 4.195633411 -0.010512986 0.288666248 0.120774865 0.949723482
1403638194545096960 7.183274746 -4.291760921 4.190650940 -0.012469971 0.289110065 0.120265074 0.949629486
1403638194595097088 7.090533257 -4.385144234 4.177208424 -0.020437630 0.290989995 0.121255763 0.948790908
1403638194645096960 7.066802025 -4.340149879 4.123403549 -0.022933785 0.288350552 0.122342363 0.949400008
1403638194695097088 7.024017811 -4.373435974 4.039444923 -0.029860497 0.286241949 0.123071834 0.949751139
1403638194745096960 6.926918030 -4.337062359 4.048174381 -0.030783946 0.288334936 0.125123218 0.948820055
1403638194795097088 6.873506546 -4.364618301 4.031464577 -0.035816796 0.289130390 0.125013754 0.948415697
1403638194845096960 6.835103035 -4.323836803 3.996991634 -0.036935061 0.288249165 0.125215307 0.948614419
1403638194895097088 6.738126278 -4.339937210 3.972082376 -0.040500961 0.290036887 0.125812680 0.947844625
1403638194945096960 6.681341171 -4.319149494 3.938784599 -0.041363370 0.289878726 0.125855163 0.947850168
1403638194995097088 6.606518269 -4.115898132 3.915260792 -0.031005105 0.289314210 0.130386218 0.947805524
1403638195045096960 6.554045677 -4.296043873 3.916502953 -0.042239461 0.290711075 0.127262369 0.947368562
1403638195095097088 6.504404068 -4.302809715 3.902195215 -0.043452233 0.290301740 0.126285523 0.947569907
1403638195145096960 6.458155155 -4.277407169 3.866311073 -0.044674374 0.289993763 0.126938522 0.947520137
1403638195195097088 6.416018963 -4.268374443 3.852073193 -0.048774589 0.288640261 0.129846692 0.947337151
1403638195245096960 6.358344078 -4.265967369 3.852586031 -0.055997089 0.287916839 0.133114442 0.946704149
1403638195295097088 6.329013824 -4.246388435 3.836258888 -0.062989153 0.285812706 0.135248482 0.946599901
1403638195345096960 6.274132252 -4.226665020 3.818691254 -0.066871561 0.285376996 0.137734741 0.946106374
1403638195395097088 6.205475807 -4.247064114 3.806590557 -0.068390563 0.286586255 0.137943566 0.945601702
1403638195445096960 6.171309471 -4.235094070 3.815650702 -0.062039573 0.287362784 0.136650667 0.945991695
1403638195495097088 6.103172779 -4.259118080 3.816408157 -0.053588297 0.290083259 0.132672712 0.946244121
1403638195545096960 6.075334549 -4.255363464 3.784070969 -0.045918293 0.290190965 0.131811425 0.946734607
1403638195595097088 6.087046623 -4.183898449 3.747909546 -0.034382761 0.288806796 0.128049523 0.948162317
1403638195645096960 6.032816887 -4.211324692 3.813328981 -0.030942662 0.291220665 0.127495214 0.947617054
1403638195695097088 5.999981403 -4.220321655 3.812340260 -0.031744398 0.291361243 0.126350924 0.947700560
1403638195745096960 5.935560226 -4.196557999 3.781042099 -0.031524606 0.290759742 0.128440976 0.947611690
1403638195795097088 5.928092957 -4.186642170 3.771996498 -0.034422211 0.288631886 0.127658129 0.948266923
1403638195845096960 5.875956535 -4.185866833 3.777544260 -0.037572958 0.288483322 0.129676089 0.947918653
1403638195895097088 5.855843544 -4.167411804 3.784296036 -0.041950356 0.287485600 0.129016414 0.948128104
1403638195945096960 5.810530663 -4.128619671 3.761103630 -0.044637527 0.286291718 0.129398167 0.948314607
1403638195995097088 5.817886353 -4.268898010 3.732357502 -0.056338511 0.285005391 0.131433710 0.947799087
1403638196045096960 5.789102077 -4.267780304 3.759862185 -0.056642745 0.285051197 0.131179571 0.947802365
1403638196095097088 5.733975887 -4.210781097 3.807521820 -0.051458936 0.286552459 0.132099032 0.947517574
1403638196145096960 5.683800697 -4.224586487 3.796909571 -0.049053010 0.287812978 0.130114719 0.947537661
1403638196195097088 5.675550461 -4.217954159 3.787144661 -0.042962324 0.287387133 0.127515912 0.948315620
1403638196245096960 5.637527466 -4.271012783 3.787914753 -0.040480100 0.289547116 0.124238931 0.948202789
1403638196295097088 5.616184235 -4.255177498 3.784171104 -0.034149189 0.289430439 0.124029391 0.948514938
1403638196345096960 5.585268974 -4.272602558 3.809288025 -0.031517107 0.291189969 0.122535512 0.948261619
1403638196395097088 5.593921661 -4.251578331 3.777508259 -0.029831849 0.287629396 0.125457421 0.949020445
1403638196445096960 5.565764904 -4.314414501 3.801588535 -0.032685991 0.288370728 0.126051605 0.948622644
1403638196495097088 5.610986710 -4.304570675 3.808561802 -0.033570021 0.286868840 0.125352040 0.949139714
1403638196545096960 5.578937531 -4.269393921 3.830036402 -0.032685071 0.287135690 0.127636164 0.948785424
1403638196595097088 5.534454346 -4.279858112 3.790811777 -0.037272833 0.285181791 0.129370838 0.948970675
1403638196645096960 5.512492180 -4.270610809 3.789553165 -0.042675145 0.285025269 0.132100984 0.948413849
1403638196695097088 5.497401237 -4.277212143 3.813733339 -0.047755636 0.284028828 0.134090438 0.948191285
1403638196745096960 5.479025841 -4.290230751 3.833086967 -0.051588796 0.284063756 0.135234833 0.947817445
1403638196795097088 5.460834503 -4.302595139 3.869135380 -0.053739164 0.284748226 0.134733915 0.947563887
1403638196845096960 5.460734367 -4.272160530 3.843256474 -0.051516898 0.283029675 0.136193275 0.947993517
1403638196895097088 5.444737434 -4.288613319 3.881177425 -0.048439633 0.284781545 0.133702382 0.947985649
1403638196945096960 5.436194420 -4.277726173 3.896692753 -0.043373171 0.284512192 0.132512167 0.948478878
1403638196995097088 5.420285225 -4.297512531 3.937625408 -0.039392367 0.286282897 0.130095556 0.948454261
1403638197045096960 5.415042877 -4.294143677 3.932751656 -0.034821652 0.286356479 0.129858807 0.948643327
1403638197095097088 5.400540829 -4.311997890 3.951900959 -0.033891164 0.287630230 0.128422871 0.948487103
1403638197145096960 5.394607067 -4.318976879 3.984598637 -0.031584293 0.288312435 0.127156585 0.948530257
1403638197195097088 5.383999825 -4.337220192 4.018445492 -0.031460881 0.289790273 0.125006422 0.948369741
1403638197245096960 5.389550209 -4.341935635 4.024134159 -0.029805876 0.289227307 0.122655861 0.948901892
1403638197295097088 5.372466087 -4.341102600 4.042912960 -0.026420167 0.292404920 0.116746895 0.948773682
1403638197345096960 5.377842903 -4.359400272 4.035895348 -0.024948157 0.293078333 0.110002950 0.949411392
1403638197395097088 5.371763229 -4.394395828 4.082243919 -0.024235273 0.295337141 0.105587989 0.949231148
1403638197445096960 5.361522675 -4.404345512 4.099468231 -0.021672482 0.296539724 0.102878638 0.949215710
1403638197495097088 5.358135223 -4.411157131 4.092782021 -0.019410841 0.296096802 0.101684660 0.949531555
1403638197545096960 5.339231491 -4.422098637 4.118028164 -0.016789759 0.296591669 0.104263313 0.949147344
1403638197595097088 5.343670368 -4.451925755 4.126783371 -0.017080385 0.295453489 0.102787562 0.949657977
1403638197645096960 5.337516785 -4.468842506 4.126818180 -0.016024437 0.295601934 0.101984441 0.949716747
1403638197695097088 5.324503422 -4.488567829 4.154843807 -0.015527095 0.295822799 0.102233835 0.949629426
1403638197745096960 5.321765900 -4.510564804 4.171746731 -0.016486321 0.294631749 0.100793399 0.950137377
1403638197795097088 5.309759617 -4.531229973 4.181625366 -0.015438266 0.294674069 0.102382921 0.949971914
1403638197845096960 5.305066109 -4.541745663 4.173172474 -0.012298497 0.292844474 0.105231255 0.950272202
1403638197895097088 5.284362316 -4.579134941 4.221490383 -0.009108426 0.292852223 0.107110552 0.950095773
1403638197945096960 5.261582375 -4.590982437 4.232548714 -0.000201143 0.292985380 0.107275955 0.950079679
1403638197995097088 5.238369942 -4.628456593 4.275818825 0.006544432 0.293322593 0.106440239 0.950047135
1403638198045096960 5.218504906 -4.634295464 4.295411110 0.011958668 0.293386251 0.107183620 0.949891150
1403638198095097088 5.218909264 -4.634765625 4.280005932 0.011368901 0.291043997 0.108531937 0.950465679
1403638198145096960 5.229391098 -4.614654064 4.301617146 0.011009447 0.286898345 0.110952765 0.951450288
1403638198195097088 5.178772926 -4.627109528 4.293891907 0.006660806 0.289245397 0.111724272 0.950689435
1403638198245096960 5.168672562 -4.628325462 4.322708130 0.003008785 0.288342863 0.112803921 0.950854659
1403638198295097088 5.133815289 -4.615461826 4.351797104 0.001050547 0.289067388 0.112531446 0.950671136
1403638198345096960 5.123575211 -4.610865116 4.392512321 -0.001068654 0.288846672 0.112017967 0.950798810
1403638198395097088 5.088977814 -4.613581181 4.422555923 -0.007037746 0.290456414 0.111023240 0.950399578
1403638198445096960 5.063224792 -4.583864689 4.415111065 -0.009976334 0.290746212 0.107944250 0.950639307
1403638198495097088 5.045015335 -4.573170185 4.411553383 -0.012814955 0.290773094 0.104159042 0.951019287
1403638198545096960 5.021645546 -4.547808170 4.445525169 -0.015234767 0.292139888 0.098676600 0.951149344
1403638198595097088 4.995453835 -4.542212486 4.462151051 -0.017365796 0.295774102 0.088968799 0.950947225
1403638198645096960 4.980628967 -4.535309792 4.479131222 -0.018280610 0.298468292 0.078540295 0.951006830
1403638198695097088 4.951362610 -4.515208244 4.516005993 -0.017999003 0.301574618 0.068625093 0.950799346
1403638198745096960 4.918654919 -4.514488697 4.526977062 -0.019434618 0.304208070 0.059081357 0.950573087
1403638198795097088 4.878495216 -4.484514236 4.537811279 -0.016104534 0.306140363 0.052816831 0.950383663
1403638198845096960 4.841010571 -4.467933178 4.542846680 -0.014978598 0.306568444 0.049940486 0.950419605
1403638198895097088 4.814381599 -4.476000309 4.570865154 -0.015492832 0.306119412 0.049973730 0.950554371
1403638198945096960 4.757247448 -4.452384472 4.582953930 -0.015205310 0.306279004 0.050006531 0.950505793
1403638198995097088 4.698584557 -4.462544918 4.643831730 -0.016097067 0.307838291 0.053195890 0.949814022
1403638199045096960 4.646939278 -4.493862152 4.711687088 -0.017703960 0.308511943 0.054919597 0.949468672
1403638199095097088 4.606477261 -4.478843689 4.682127476 -0.017479563 0.306750655 0.057857469 0.949868917
1403638199145096960 4.559869766 -4.477030277 4.679455280 -0.016659558 0.304494053 0.057749428 0.950616002
1403638199195097088 4.493538380 -4.481651306 4.687242985 -0.014737571 0.303716183 0.059842736 0.950767159
1403638199245096960 4.441203594 -4.496915340 4.680683613 -0.011971527 0.301976621 0.061936680 0.951225877
1403638199295097088 4.386117458 -4.533944607 4.739598274 -0.011228848 0.302556366 0.060421761 0.951148152
1403638199345096960 4.283795357 -4.589242935 4.801946640 -0.011786839 0.305302620 0.058844741 0.950362384
1403638199395097088 4.208662033 -4.602360725 4.815283298 -0.011570079 0.306778371 0.056758691 0.950016677
1403638199445096960 4.147481918 -4.635058880 4.826299667 -0.014999755 0.306510955 0.054065358 0.950212061
1403638199495097088 4.079993248 -4.648899555 4.843949795 -0.016984196 0.307648808 0.053333264 0.949852288
1403638199545096960 3.992983818 -4.659133434 4.854124069 -0.019700984 0.307806343 0.051096734 0.949871719
1403638199595097088 3.915351629 -4.704773426 4.881780624 -0.023957364 0.305721879 0.049298465 0.950541854
1403638199645096960 3.839475155 -4.730409145 4.855685234 -0.024784517 0.299877405 0.049909212 0.952348828
1403638199695097088 3.735778809 -4.739106178 4.826603889 -0.021040032 0.292665780 0.053446181 0.954488099
1403638199745096960 3.654976130 -4.810514450 4.844200611 -0.025456937 0.285847217 0.054163001 0.956404567
1403638199795097088 3.562170506 -4.839169979 4.866881371 -0.024140568 0.278620094 0.064600885 0.957922161
1403638199845096960 3.463418484 -4.847179413 4.891922951 -0.021757212 0.273528159 0.070418164 0.959036112
1403638199895097088 3.373702049 -4.854403973 4.897211075 -0.019681923 0.267446607 0.077552117 0.960245073
1403638199945096960 3.273135185 -4.898028374 4.924764633 -0.021010447 0.263306558 0.080225028 0.961141050
1403638199995097088 3.195287466 -4.929895878 4.944109917 -0.021243718 0.258630544 0.079726331 0.962446213
1403638200045096960 3.126190662 -4.948184013 4.996353149 -0.020820297 0.253460824 0.079178117 0.963874996
1403638200095097088 2.997819424 -4.987018585 4.994048119 -0.022886055 0.249552190 0.075242475 0.965162456
1403638200145096960 2.881444931 -5.009231091 5.047054291 -0.019871509 0.247982249 0.072681122 0.965829909
1403638200195097088 2.800746441 -5.028498173 5.089776993 -0.017460430 0.241558731 0.059069559 0.968429267
1403638200245096960 2.723652124 -5.078283310 5.102514744 -0.015101350 0.233141571 0.054367475 0.970804393
1403638200295097088 2.606534481 -5.113576412 5.117901325 -0.011268129 0.226855576 0.049132101 0.972623050
1403638200345096960 2.522103548 -5.137610912 5.125705242 -0.006594189 0.217095420 0.045313794 0.975075781
1403638200395097088 2.443932533 -5.132927895 5.188306808 0.000685983 0.210003942 0.040540174 0.976859450
1403638200445096960 2.316190481 -5.178018093 5.185888290 -0.001483439 0.203872681 0.033004791 0.978439808
1403638200495097088 2.195306063 -5.199886799 5.168849468 -0.001638460 0.198946431 0.026489208 0.979650974
1403638200545096960 2.089344740 -5.220026016 5.198530197 -0.001173323 0.194095910 0.021090651 0.980755091
1403638200595097088 1.960820079 -5.250457764 5.188712597 -0.001932357 0.187384114 0.015941925 0.982155442
1403638200645096960 1.859535456 -5.256806374 5.194368362 0.000348232 0.180370480 0.008257171 0.983564079
1403638200695097088 1.753420115 -5.291555405 5.195630074 -0.001039748 0.173958421 0.000336354 0.984752417
1403638200745096960 1.633130908 -5.329729080 5.173860073 -0.003255253 0.167488769 -0.001809523 0.985866964
1403638200795097088 1.535998464 -5.364609718 5.233523369 -0.006755904 0.162551865 -0.006862081 0.986653030
1403638200845096960 1.422834039 -5.404104710 5.238499641 -0.008760486 0.157982424 -0.007092905 0.987377584
1403638200895097088 1.269537449 -5.443656445 5.254622936 -0.011214945 0.154491916 -0.006029615 0.987911999
1403638200945096960 1.192561865 -5.482491970 5.214540005 -0.012339046 0.143978834 0.000289372 0.989503801
1403638200995097088 1.039932251 -5.499688148 5.259635925 -0.009528810 0.143034145 0.008118693 0.989638567
1403638201045096960 0.904157102 -5.533787727 5.279340267 -0.008143457 0.139375716 0.014292396 0.990102947
1403638201095097088 0.823963284 -5.549180984 5.279474735 -0.006611019 0.134008169 0.017059879 0.990811288
1403638201145096960 0.697088599 -5.568185806 5.293037415 -0.006487814 0.132930338 0.020959204 0.990882516
1403638201195097088 0.546672642 -5.593612671 5.313279152 -0.004865682 0.133389235 0.024416681 0.990750968
1403638201245096960 0.445330918 -5.609598637 5.310194969 -0.002586405 0.130701318 0.027770065 0.991029382
1403638201295097088 0.354017258 -5.614035606 5.309452534 -0.002860563 0.129129291 0.027596358 0.991239548
1403638201345096960 0.193035603 -5.640340328 5.344927311 -0.004425720 0.132525206 0.027608557 0.990785182
1403638201395097088 0.090120673 -5.646397114 5.346371651 -0.004003164 0.132295415 0.025923146 0.990863204
1403638201445096960 -0.031387329 -5.661878109 5.348899841 -0.003322499 0.132335588 0.026377536 0.990848362
1403638201495097088 -0.148874879 -5.670892239 5.373023987 -0.002401375 0.133316189 0.026006382 0.990729392
1403638201545096960 -0.275628209 -5.669434071 5.396217346 -0.000618438 0.134728223 0.025122842 0.990563869
1403638201595097088 -0.396404147 -5.682796001 5.395937920 -0.000142441 0.135366544 0.024356987 0.990496159
1403638201645096960 -0.515239477 -5.689584732 5.398128510 0.001272219 0.135251150 0.025116283 0.990492165
1403638201695097088 -0.614323854 -5.685857773 5.407703400 0.002144786 0.134095222 0.025548968 0.990636706
1403638201745096960 -0.750257969 -5.689626217 5.444955826 0.002310065 0.135962635 0.026322503 0.990361512
1403638201795097088 -0.856385469 -5.691094875 5.447316170 0.001741912 0.135916963 0.024924522 0.990405142
1403638201845096960 -0.973547578 -5.694955826 5.449104309 0.002699303 0.133795321 0.027097974 0.990634799
1403638201895097088 -1.095808983 -5.683045864 5.443674088 0.001394077 0.133166507 0.026876569 0.990728199
1403638201945096960 -1.221661329 -5.713526249 5.483054161 -0.000392334 0.131992862 0.026748655 0.990889609
1403638201995097088 -1.319461346 -5.721040726 5.474615574 -0.001430321 0.125992030 0.025787069 0.991694987
1403638202045096960 -1.440983295 -5.715418816 5.485533714 -0.001225945 0.120806761 0.025670735 0.992343307
1403638202095097088 -1.553719640 -5.715967655 5.461399078 -0.002718868 0.113732927 0.029341439 0.993074298
1403638202145096960 -1.665075660 -5.719032288 5.450187683 -0.006359900 0.107286908 0.032010026 0.993692338
1403638202195097088 -1.838698864 -5.711267471 5.511174679 -0.007408518 0.107028842 0.035820886 0.993582785
1403638202245096960 -1.959614038 -5.717308998 5.505964756 -0.011214682 0.102239549 0.038788483 0.993939996
1403638202295097088 -2.067718744 -5.712584972 5.497745991 -0.014965655 0.098089680 0.039602488 0.994276643
1403638202345096960 -2.207091331 -5.725491047 5.491373539 -0.015697137 0.094854712 0.042161766 0.994473994
1403638202395097088 -2.286151171 -5.729580879 5.445912361 -0.019002860 0.091176003 0.039166920 0.994882822
1403638202445096960 -2.404751778 -5.726830482 5.503500462 -0.017971059 0.090616226 0.039829560 0.994926810
1403638202495097088 -2.528043270 -5.725288391 5.496183395 -0.018664740 0.089140221 0.039410658 0.995064020
1403638202545096960 -2.668838978 -5.724854469 5.512836456 -0.019095570 0.088918865 0.041990802 0.994970143
1403638202595097088 -2.755773306 -5.741226673 5.470641613 -0.021583503 0.085211456 0.042777639 0.995210171
1403638202645096960 -2.857338428 -5.747688293 5.453751564 -0.023958018 0.083370984 0.043803610 0.995267034
1403638202695097088 -2.999257565 -5.773708344 5.401573658 -0.026473500 0.082262069 0.045619626 0.995214045
1403638202745096960 -2.955850601 -5.766613960 5.516814232 -0.025473505 0.079290606 0.042709097 0.995610416
1403638202795097088 -3.062044144 -5.761841297 5.512125015 -0.024905067 0.078866631 0.042268507 0.995677233
1403638202845096960 -3.167072773 -5.748882771 5.507086754 -0.023452356 0.078362174 0.041583028 0.995781183
1403638202895097088 -3.289774179 -5.744992733 5.507634640 -0.023066223 0.079089575 0.040581673 0.995774031
1403638202945096960 -3.403958797 -5.732513905 5.513397694 -0.022954879 0.079052657 0.041476618 0.995742619
1403638202995097088 -3.512038231 -5.735344410 5.499907970 -0.022603059 0.078813471 0.042695407 0.995718122
1403638203045096960 -3.583880663 -5.784835815 5.588345528 -0.022939900 0.079724483 0.043356903 0.995609343
1403638203095097088 -3.679335356 -5.784061909 5.580069065 -0.022941541 0.078564487 0.043213915 0.995707750
1403638203145096960 -3.790931940 -5.778224468 5.586814880 -0.021631084 0.079558499 0.041388370 0.995735705
1403638203195097088 -3.884835482 -5.778742790 5.564453602 -0.019257730 0.079419665 0.038044740 0.995928824
1403638203245096960 -3.977324963 -5.784383297 5.558678627 -0.016840324 0.078502819 0.037896939 0.996050954
1403638203295097088 -4.104207993 -5.781039715 5.576967239 -0.013914705 0.079806417 0.037680548 0.996000707
1403638203345096960 -4.236162186 -5.806322575 5.711550713 -0.013363016 0.085050657 0.038995981 0.995523572
1403638203395097088 -4.338662624 -5.803661346 5.710694790 -0.011114067 0.084134832 0.039208725 0.995620668
1403638203445096960 -4.438512802 -5.807101727 5.715430260 -0.010812121 0.083530210 0.040247936 0.995633423
1403638203495097088 -4.534833908 -5.809850216 5.701759815 -0.012017939 0.082938001 0.040528346 0.995657682
1403638203545096960 -4.631596565 -5.808013916 5.694444656 -0.012600222 0.082076244 0.041989569 0.995661378
1403638203595097088 -4.736606598 -5.793318272 5.761434078 -0.011314342 0.084346704 0.045448415 0.995335162
1403638203645096960 -4.839448452 -5.785992146 5.756853580 -0.013508983 0.084598355 0.044286359 0.995338798
1403638203695097088 -4.927052498 -5.785196781 5.751793385 -0.013005157 0.083284467 0.045644771 0.995394945
1403638203745096960 -5.023091793 -5.782567978 5.748343945 -0.012503774 0.082972199 0.045022681 0.995455801
1403638203795097088 -5.112835884 -5.780478477 5.746426582 -0.012440247 0.083269775 0.043690383 0.995491087
1403638203845096960 -5.156177044 -5.767479897 5.805414200 -0.010136902 0.083367139 0.044445880 0.995475650
1403638203895097088 -5.240410328 -5.772724628 5.796576023 -0.009707352 0.082285009 0.043828033 0.995597363
1403638203945096960 -5.330888271 -5.777714729 5.785395622 -0.010710668 0.081605017 0.043795101 0.995644450
1403638203995097088 -5.417164803 -5.785887718 5.769435883 -0.010862864 0.080746345 0.044477355 0.995682597
1403638204045096960 -5.483101368 -5.782786846 5.791592121 -0.011711229 0.080159396 0.045694821 0.995665252
1403638204095097088 -5.597953320 -5.803070545 5.738636971 -0.014287204 0.078867525 0.044885896 0.995771587
1403638204145096960 -5.651355743 -5.802834034 5.773227692 -0.016082862 0.078713924 0.047742173 0.995623469
1403638204195097088 -5.733145237 -5.811401367 5.759176254 -0.017688036 0.077097178 0.050894741 0.995566607
1403638204245096960 -5.812553883 -5.822996140 5.751789093 -0.020457402 0.075878523 0.054629307 0.995409250
1403638204295097088 -5.893411636 -5.841539383 5.718623161 -0.024194952 0.071560942 0.060171932 0.995325565
1403638204345096960 -5.967842102 -5.848374367 5.729105949 -0.027692286 0.071482763 0.068398453 0.994708478
1403638204395097088 -6.037113190 -5.858241081 5.721534252 -0.031465612 0.069878504 0.074739836 0.994253933
1403638204445096960 -6.109924793 -5.873242378 5.705883980 -0.033281073 0.068804435 0.078526996 0.993977785
1403638204495097088 -6.183317661 -5.885373116 5.695288658 -0.034189574 0.069470614 0.079993807 0.993783593
1403638204545096960 -6.241215706 -5.890673637 5.689783096 -0.032972429 0.068295747 0.081834659 0.993756354
1403638204595097088 -6.316608906 -5.909118652 5.664894581 -0.031059245 0.068332911 0.080919854 0.993890285
1403638204645096960 -6.365588188 -5.908092976 5.671065331 -0.029923633 0.065606341 0.079497509 0.994223595
1403638204695097088 -6.427523613 -5.913089275 5.667105198 -0.029435523 0.063301705 0.075243391 0.994718492
1403638204745096960 -6.519741535 -5.927026272 5.624269485 -0.030432280 0.061062682 0.065158531 0.995539844
1403638204795097088 -6.548710346 -5.928911209 5.637532234 -0.029677505 0.055035312 0.059927419 0.996242464
1403638204845096960 -6.638629913 -5.938616753 5.600772381 -0.029078173 0.051629033 0.045798339 0.997191787
1403638204895097088 -6.682209015 -5.931977749 5.607471943 -0.025915882 0.043272547 0.033798035 0.998155057
1403638204945096960 -6.733875751 -5.933112621 5.591189861 -0.024894893 0.032938827 0.023191513 0.998878062
1403638204995097088 -6.786239147 -5.925916672 5.586585999 -0.023472667 0.019688258 0.012285529 0.999455094
1403638205045096960 -6.821915627 -5.919926167 5.594461918 -0.021476895 0.004115051 0.003525380 0.999754667
1403638205095097088 -6.865158558 -5.909354210 5.584681034 -0.020806713 -0.013867716 -0.006650954 0.999665201
1403638205145096960 -6.911840916 -5.751532078 5.896603107 -0.007828541 -0.030089948 -0.011842040 0.999446392
1403638205195097088 -6.954295635 -5.728114605 5.928794384 -0.003780889 -0.052188210 -0.019643249 0.998436928
1403638205245096960 -6.956688881 -5.740856647 5.932236671 -0.004298568 -0.079002015 -0.031429645 0.996369600
1403638205295097088 -7.126130104 -5.715229988 5.998363972 0.001352568 -0.093978658 -0.037837725 0.994853973
1403638205345096960 -7.184054375 -5.713654041 6.011073112 0.004281621 -0.116210029 -0.044139255 0.992234170
1403638205395097088 -7.326931953 -5.700395107 6.073030472 0.010066005 -0.132546097 -0.053970426 0.989655197
1403638205445096960 -7.288381100 -5.719751358 5.988351345 0.012713185 -0.159363925 -0.062160581 0.985178947
1403638205495097088 -7.340764046 -5.725940704 5.986720562 0.017576883 -0.176531732 -0.074029244 0.981349707
1403638205545096960 -7.456929207 -5.697808266 6.084933758 0.025434351 -0.184472665 -0.082900330 0.979004860
1403638205595097088 -7.517587185 -5.722135544 6.028340340 0.029058110 -0.195518911 -0.095800571 0.975576878
1403638205645096960 -7.572700024 -5.707918167 6.070902348 0.037784923 -0.202760026 -0.102458075 0.973120272
1403638205695097088 -7.615954876 -5.728226662 6.051806927 0.043419920 -0.210516497 -0.111410528 0.970250070
1403638205745096960 -7.668052673 -5.739668369 6.036371708 0.048502028 -0.217723131 -0.117172487 0.967736959
1403638205795097088 -7.596010208 -5.750843048 5.999469757 0.051740713 -0.231795028 -0.120553613 0.963877976
1403638205845096960 -7.759791851 -5.776020527 6.021036148 0.049598392 -0.233091459 -0.125471666 0.963049948
1403638205895097088 -7.716396332 -5.781349182 5.958237171 0.051346991 -0.251130968 -0.128779471 0.957973123
1403638205945096960 -7.765476704 -5.794820786 5.924991608 0.051564835 -0.263509393 -0.131178424 0.954303980
1403638205995097088 -7.821877480 -5.804643631 5.887217522 0.049663261 -0.276350915 -0.130224913 0.950897038
1403638206045096960 -7.983496189 -5.832461357 5.905638695 0.045432556 -0.281425625 -0.132731512 0.949272275
1403638206095097088 -8.255059242 -5.782338142 5.875843048 0.051534284 -0.276949763 -0.136436030 0.949751675
1403638206145096960 -8.321649551 -5.788700104 5.839985847 0.053496931 -0.289232224 -0.137893468 0.945763290
1403638206195097088 -8.379307747 -5.797448635 5.806235790 0.054914322 -0.301580399 -0.138274997 0.941760957
1403638206245096960 -8.457944870 -5.814915180 5.775801659 0.055807527 -0.313239694 -0.142447934 0.937269986
1403638206295097088 -8.503265381 -5.841654778 5.718770981 0.054811317 -0.324897140 -0.142832100 0.933293343
1403638206345096960 -8.571740150 -5.848705292 5.674242020 0.054003168 -0.336713761 -0.138716802 0.929766178
1403638206395097088 -8.378500938 -5.856573582 5.663685799 0.053169288 -0.365583420 -0.123968855 0.920952499
1403638206445096960 -8.449171066 -5.877224922 5.613074303 0.050593220 -0.372953534 -0.121532999 0.918463767
1403638206495097088 -8.512661934 -5.872239113 5.569571495 0.052975584 -0.378561765 -0.118695617 0.916403770
1403638206545096960 -8.573279381 -5.875512123 5.522153854 0.053307019 -0.383689106 -0.116237596 0.914565384
1403638206595097088 -8.634919167 -5.872123241 5.474767685 0.055194169 -0.387170613 -0.115868457 0.913031757
1403638206645096960 -8.688699722 -5.866321564 5.421730995 0.056209765 -0.390218884 -0.112788126 0.912057281
1403638206695097088 -8.747758865 -5.867193222 5.375105858 0.056249663 -0.395195872 -0.111036569 0.910124779
1403638206745096960 -8.836866379 -5.833959579 5.344354630 0.057247829 -0.399225056 -0.110914931 0.908317089
1403638206795097088 -8.887845993 -5.819602013 5.294638634 0.057565998 -0.405021697 -0.110204376 0.905813754
1403638206845096960 -8.942944527 -5.820408821 5.244041443 0.056239720 -0.408362657 -0.113016546 0.904048800
1403638206895097088 -9.006114960 -5.806969643 5.189629078 0.057476480 -0.411531746 -0.112941615 0.902542114
1403638206945096960 -9.063871384 -5.779094219 5.135484695 0.061299220 -0.412794471 -0.112133384 0.901814401
1403638206995097088 -9.096901894 -5.778916359 5.085410118 0.061101701 -0.418207884 -0.110250689 0.899562955
1403638207045096960 -9.150585175 -5.763756275 5.024594307 0.061877485 -0.419120759 -0.110213652 0.899089515
1403638207095097088 -9.215811729 -5.735443115 4.978699684 0.065141216 -0.419101417 -0.109490484 0.898956358
1403638207145096960 -9.255733490 -5.708463192 4.927082062 0.066210248 -0.420472383 -0.109842159 0.898194790
1403638207195097088 -9.293397903 -5.698277473 4.871364117 0.065196939 -0.423589110 -0.109028034 0.896902740
1403638207245096960 -10.043458939 -5.304220676 4.931503773 0.114079341 -0.347856551 -0.111930199 0.923825443
1403638207295097088 -9.383129120 -5.637711048 4.768612862 0.068330377 -0.429619938 -0.108835004 0.893819094
1403638207345096960 -9.419187546 -5.607624531 4.707417965 0.069632739 -0.435552239 -0.108370572 0.890899181
1403638207395097088 -10.175602913 -5.224615097 4.800518036 0.117863178 -0.365713924 -0.114198484 0.916144252
1403638207445096960 -10.220237732 -5.180653572 4.744501114 0.119876221 -0.373055369 -0.117479794 0.912500858
1403638207495097088 -10.168840408 -5.221836567 4.944883347 0.126769230 -0.389644116 -0.123243086 0.903835237
1403638207545096960 -10.203723907 -5.195811272 4.901164055 0.123586841 -0.400405943 -0.126411751 0.899122596
1403638207595097088 -10.238728523 -5.166921139 4.845692635 0.119834937 -0.407300860 -0.133707732 0.895470738
1403638207645096960 -10.271315575 -5.133789062 4.785483360 0.113129117 -0.414754599 -0.135751322 0.892609656
1403638207695097088 -10.302196503 -5.105887413 4.738010406 0.105498783 -0.421440631 -0.139888003 0.889769137
1403638207745096960 -10.322583199 -5.086837769 4.673282623 0.098931454 -0.426620364 -0.141107783 0.887860477
1403638207795097088 -10.348601341 -5.060574532 4.633174896 0.094476826 -0.432320386 -0.143624425 0.885180891
1403638207845096960 -10.280521393 -5.120080471 4.596671104 0.089169800 -0.429540515 -0.153329030 0.885456920
1403638207895097088 -10.304900169 -5.093365669 4.536447525 0.083455525 -0.431373626 -0.156198353 0.884620845
1403638207945096960 -10.324840546 -5.070595741 4.477961540 0.079518467 -0.433231622 -0.158446342 0.883675218
1403638207995097088 -10.344307899 -5.046758175 4.425335884 0.078941017 -0.434212327 -0.160223678 0.882924914
1403638208045096960 -10.360320091 -5.028070450 4.370625019 0.077188291 -0.435714543 -0.160970822 0.882203639
1403638208095097088 -10.389343262 -5.010629177 4.312716484 0.078793891 -0.434685767 -0.158316791 0.883049011
1403638208145096960 -10.406350136 -4.988195419 4.256086349 0.080381706 -0.436136305 -0.155264780 0.882732511
1403638208195097088 -10.427314758 -4.962588310 4.211963177 0.085121401 -0.436894923 -0.153371006 0.882243991
1403638208245096960 -10.443820000 -4.933483124 4.153067112 0.088075027 -0.435893327 -0.152969763 0.882519186
1403638208295097088 -10.458168983 -4.910695076 4.104235649 0.088303395 -0.435269147 -0.153002217 0.882798731
1403638208345096960 -10.470673561 -4.888052464 4.050963402 0.085565574 -0.434257805 -0.154172212 0.883362710
1403638208395097088 -10.484781265 -4.851964951 4.015563965 0.083661117 -0.433796316 -0.155120596 0.883605778
1403638208445096960 -10.500663757 -4.815720081 3.952059746 0.081997044 -0.432193965 -0.157609105 0.884106457
1403638208495097088 -10.505565643 -4.792469501 3.916631222 0.079778537 -0.434258759 -0.157647669 0.883290410
1403638208545096960 -10.514733315 -4.769474030 3.872918606 0.076913111 -0.437819093 -0.159178957 0.881510556
1403638208595097088 -10.524442673 -4.731800556 3.818732738 0.077121176 -0.441802651 -0.163793370 0.878654897
1403638208645096960 -10.508573532 -4.738164902 3.771777153 0.074575253 -0.446799964 -0.164109215 0.876285613
1403638208695097088 -10.544436455 -4.685100555 3.729963541 0.076203488 -0.452491373 -0.166074485 0.872848094
1403638208745096960 -10.548940659 -4.664489746 3.679615974 0.075304821 -0.457971632 -0.166697830 0.869944274
1403638208795097088 -10.555126190 -4.637507439 3.630494118 0.076035149 -0.462474823 -0.167903900 0.867262363
1403638208845096960 -10.556388855 -4.629903793 3.582577944 0.075890951 -0.466011286 -0.167546317 0.865449190
1403638208895097088 -10.568552971 -4.597720146 3.536450863 0.078240849 -0.469238073 -0.170872658 0.862842083
1403638208945096960 -10.553806305 -4.602277279 3.494059086 0.077464208 -0.471798331 -0.171221912 0.861445725
1403638208995097088 -10.552803993 -4.580664158 3.443133831 0.078042150 -0.473462731 -0.172493801 0.860225737
1403638209045096960 -10.551194191 -4.555526257 3.399329662 0.078410953 -0.475575656 -0.172907501 0.858942688
1403638209095097088 -10.564068794 -4.523495674 3.363312244 0.078340590 -0.477914095 -0.173400223 0.857550681
1403638209145096960 -10.569217682 -4.497271061 3.317246437 0.078194596 -0.478285223 -0.173964754 0.857242763
1403638209195097088 -10.563139915 -4.472844124 3.288253307 0.077608280 -0.480049878 -0.174348533 0.856231034
1403638209245096960 -10.560413361 -4.445407391 3.248451233 0.077511303 -0.480917841 -0.174309894 0.855760515
1403638209295097088 -10.559759140 -4.420995235 3.214078903 0.076207146 -0.482094646 -0.173306987 0.855419159
1403638209345096960 -10.563544273 -4.383358002 3.174708366 0.075402588 -0.482164949 -0.173562095 0.855399132
1403638209395097088 -10.555719376 -4.356757164 3.140653849 0.074833550 -0.483239114 -0.172311857 0.855095625
1403638209445096960 -10.551765442 -4.328626156 3.105566025 0.073901780 -0.483187765 -0.172298834 0.855208278
1403638209495097088 -10.542986870 -4.299048424 3.072432995 0.075262159 -0.484186739 -0.170308173 0.854923368
1403638209545096960 -10.537910461 -4.263373852 3.049682856 0.077496804 -0.484750360 -0.169673026 0.854530513
1403638209595097088 -10.531602859 -4.226187229 3.016563416 0.078012869 -0.484714538 -0.168443918 0.854747057
1403638209645096960 -10.524265289 -4.184378147 2.983387470 0.077298589 -0.484433174 -0.167788059 0.855100334
1403638209695097088 -10.518663406 -4.133357048 2.958830357 0.076090485 -0.483705759 -0.167903230 0.855597734
1403638209745096960 -10.512338638 -4.083058357 2.936745405 0.076015137 -0.482885629 -0.168740526 0.855902910
1403638209795097088 -10.505520821 -4.029184341 2.913172007 0.077963144 -0.481342226 -0.170864165 0.856175721
1403638209845096960 -10.495798111 -3.973547935 2.893421173 0.078845777 -0.480418682 -0.171826079 0.856421053
1403638209895097088 -10.490018845 -3.915746689 2.882197380 0.081448235 -0.480103552 -0.172505498 0.856217623
1403638209945096960 -10.478441238 -3.859677792 2.867228031 0.084240176 -0.480062515 -0.172071904 0.856057763
1403638209995097088 -10.468153954 -3.801225185 2.858336687 0.087650254 -0.480629951 -0.171286389 0.855554342
1403638210045096960 -10.455126762 -3.744018316 2.843766212 0.091209531 -0.481002152 -0.169724628 0.855284333
1403638210095097088 -10.444834709 -3.683196545 2.822075367 0.094552130 -0.481287330 -0.167553559 0.855189025
1403638210145096960 -10.435433388 -3.621226788 2.800384998 0.096763276 -0.481488347 -0.165269703 0.855272889
1403638210195097088 -10.418745041 -3.567595005 2.796431065 0.100189492 -0.482865423 -0.163881510 0.854368746
1403638210245096960 -10.398571968 -3.515449286 2.774913788 0.099321164 -0.483288735 -0.162769392 0.854443371
1403638210295097088 -10.376866341 -3.453795910 2.757825375 0.099717878 -0.483254969 -0.163078219 0.854357362
1403638210345096960 -10.350166321 -3.399754047 2.739478111 0.099640943 -0.482871145 -0.163810581 0.854443252
1403638210395097088 -10.335006714 -3.350670338 2.728303909 0.097498156 -0.483290821 -0.163962841 0.854423940
1403638210445096960 -10.316668510 -3.303147793 2.661215305 0.095085576 -0.480147541 -0.163782239 0.856500089
1403638210495097088 -10.291986465 -3.252892256 2.652426720 0.094624922 -0.480980963 -0.162700891 0.856289566
1403638210545096960 -10.262865067 -3.189234495 2.629533291 0.095322341 -0.480744094 -0.162543088 0.856375217
1403638210595097088 -10.234734535 -3.135349512 2.609568119 0.095112905 -0.480183303 -0.162761867 0.856671512
1403638210645096960 -10.205945015 -3.072172880 2.573405504 0.095305577 -0.479581028 -0.160741597 0.857368648
1403638210695097088 -10.176672935 -3.007712841 2.553249121 0.094079047 -0.479908854 -0.158658087 0.857708693
1403638210745096960 -10.137126923 -2.956161261 2.548484325 0.094571561 -0.480993092 -0.159478441 0.856894672
1403638210795097088 -10.099329948 -2.900410175 2.536762238 0.093908913 -0.481390089 -0.159485653 0.856743276
1403638210845096960 -10.059889793 -2.855574131 2.516083241 0.090905778 -0.481257319 -0.160076708 0.857031465
1403638210895097088 -10.021671295 -2.789017916 2.493022442 0.088096306 -0.481383622 -0.160094604 0.857250571
1403638210945096960 -9.980465889 -2.737278461 2.467392921 0.084711574 -0.480476201 -0.162604034 0.857628405
1403638210995097088 -9.939564705 -2.695867062 2.444254637 0.080456778 -0.480453044 -0.163621187 0.857857645
1403638211045096960 -9.888821602 -2.629800558 2.420021534 0.078649864 -0.480514556 -0.164162174 0.857887387
1403638211095097088 -9.835840225 -2.580872774 2.384677887 0.075041763 -0.480104744 -0.164709941 0.858334899
1403638211145096960 -9.794395447 -2.551817656 2.367558479 0.071522929 -0.480360687 -0.166532472 0.858140469
1403638211195097088 -9.753296852 -2.500016451 2.329607964 0.068632863 -0.480145633 -0.165691808 0.858659327
1403638211245096960 -9.689350128 -2.459693193 2.308343649 0.067374282 -0.480578393 -0.166891769 0.858284473
1403638211295097088 -9.633647919 -2.437803745 2.303170681 0.065823264 -0.481197387 -0.167796791 0.857881486
1403638211345096960 -9.590038300 -2.417867899 2.272455692 0.063651577 -0.479006231 -0.168545097 0.859124005
1403638211395097088 -9.523163795 -2.389916658 2.258932352 0.063967183 -0.476605713 -0.167213917 0.860694289
1403638211445096960 -9.476222992 -2.359131813 2.217743397 0.061746519 -0.470899135 -0.166561022 0.864117324
1403638211495097088 -9.442859650 -2.330240250 2.190471411 0.061070818 -0.464929283 -0.165007442 0.867688656
1403638211545096960 -9.393531799 -2.266299725 2.149523258 0.060979571 -0.457192659 -0.160524756 0.872632861
1403638211595097088 -9.334016800 -2.217301607 2.114029884 0.060147893 -0.449851871 -0.155687571 0.877369285
1403638211645096960 -9.258630753 -2.196038485 2.131796837 0.059689760 -0.444353819 -0.151744321 0.880886137
1403638211695097088 -9.160481453 -2.124096155 2.144845247 0.061051473 -0.437561065 -0.144380391 0.885419309
1403638211745096960 -9.110393524 -2.077735901 2.109720230 0.058820300 -0.426263541 -0.138933510 0.891928792
1403638211795097088 -9.070859909 -2.032508612 2.093998432 0.057232976 -0.415049195 -0.131415963 0.898436606
1403638211845096960 -8.995015144 -1.946205258 2.080370903 0.056186300 -0.404487759 -0.122545756 0.904552519
1403638211895097088 -8.903541565 -1.918959379 2.082149029 0.053732026 -0.394227266 -0.115634248 0.910124421
1403638211945096960 -8.831160545 -1.923663974 2.096814632 0.052007325 -0.383873343 -0.112044014 0.915086091
1403638211995097088 -8.756468773 -1.859096169 2.140537977 0.052831315 -0.374410331 -0.105491966 0.919726670
1403638212045096960 -8.606241226 -1.877607107 2.201956749 0.051989976 -0.368090957 -0.103145361 0.922587156
1403638212095097088 -8.553464890 -1.895975709 2.162665129 0.049761914 -0.354560345 -0.099805281 0.928358555
1403638212145096960 -8.467467308 -1.906879425 2.209495306 0.049774677 -0.345269531 -0.098845869 0.931955457
1403638212195097088 -8.346634865 -1.912185669 2.218767881 0.050022539 -0.333473682 -0.096654356 0.936456621
1403638212245096960 -8.291666031 -1.875031233 2.201987028 0.051195469 -0.321226686 -0.092858404 0.941047132
1403638212295097088 -8.200786591 -1.838457465 2.179517031 0.053231314 -0.309384614 -0.089607373 0.945207953
1403638212345096960 -8.127011299 -1.821117401 2.177867889 0.052391656 -0.297455221 -0.086220518 0.949390054
1403638212395097088 -8.039427757 -1.768635273 2.162178278 0.056233998 -0.284709483 -0.082873873 0.953367829
1403638212445096960 -7.970144272 -1.782687783 2.160491467 0.053108402 -0.272855759 -0.078738742 0.957355440
1403638212495097088 -7.895765781 -1.758296013 2.155823708 0.055744972 -0.261437774 -0.073565759 0.960797012
1403638212545096960 -7.817342281 -1.744249582 2.134820223 0.054556694 -0.250036776 -0.067459814 0.964341402
1403638212595097088 -7.742200851 -1.732801795 2.115289211 0.054125525 -0.237214431 -0.063619800 0.967859626
1403638212645096960 -7.673741341 -1.720007539 2.091824770 0.053002860 -0.224884063 -0.056796886 0.971283674
1403638212695097088 -7.593624592 -1.705151796 2.072685480 0.053065706 -0.212577686 -0.052917726 0.974266112
1403638212745096960 -7.516912937 -1.694867849 2.065270662 0.051794287 -0.199228853 -0.050149873 0.977297425
1403638212795097088 -7.438400745 -1.688284039 2.044339180 0.053129185 -0.186354786 -0.044333905 0.980042696
1403638212845096960 -7.362860203 -1.680632353 2.028555393 0.052700210 -0.172881365 -0.039252792 0.982748151
1403638212895097088 -7.283985138 -1.675921440 2.010515213 0.051482882 -0.159990713 -0.032026809 0.985254705
1403638212945096960 -7.204065800 -1.673555136 1.987060428 0.051428147 -0.145417571 -0.027098808 0.987661123
1403638212995097088 -7.120663643 -1.669884443 1.963442087 0.049844891 -0.130577058 -0.021823896 0.989943862
1403638213045096960 -7.035489082 -1.670149088 1.959855914 0.049779419 -0.116675034 -0.014828201 0.991810977
1403638213095097088 -6.952563286 -1.666828156 1.942391396 0.048983537 -0.102141872 -0.008345423 0.993528068
1403638213145096960 -6.876923084 -1.671764970 1.914363146 0.046118304 -0.087142743 0.000813483 0.995127439
1403638213195097088 -6.789972305 -1.668701410 1.901790023 0.042689398 -0.073677994 0.008398019 0.996332586
1403638213245096960 -6.706757545 -1.664860725 1.881415606 0.036747947 -0.060264502 0.019219741 0.997320592
1403638213295097088 -6.606274605 -1.652706504 1.879005194 0.032710727 -0.049432475 0.027682044 0.997857809
1403638213345096960 -6.525045395 -1.654360771 1.871041298 0.025264882 -0.036509637 0.038320437 0.998278677
1403638213395097088 -6.441808701 -1.641816854 1.851521373 0.021672586 -0.023702398 0.049282681 0.998268366
1403638213445096960 -6.354249001 -1.635735989 1.843230486 0.017213633 -0.010765938 0.061381593 0.997907817
1403638213495097088 -6.252771854 -1.630445480 1.833146691 0.015764419 0.001140908 0.071433417 0.997320175
1403638213545096960 -6.153782845 -1.627402425 1.829647541 0.015257278 0.013397347 0.077939674 0.996751249
1403638213595097088 -6.056574821 -1.625332952 1.832443118 0.020008789 0.026809128 0.077663161 0.996418297
1403638213645096960 -5.955066204 -1.621048093 1.829607129 0.027194938 0.039591774 0.073580936 0.996131897
1403638213695097088 -5.847918034 -1.621900082 1.821382046 0.034493323 0.049963385 0.068610407 0.995794415
1403638213745096960 -5.743979454 -1.625179648 1.823203802 0.040748168 0.059385471 0.062197790 0.995461881
1403638213795097088 -5.644091129 -1.623391867 1.819930553 0.045432709 0.067378297 0.057063021 0.995057702
1403638213845096960 -5.542922497 -1.625568151 1.817795634 0.048162423 0.073410071 0.052820627 0.994736791
1403638213895097088 -5.434551239 -1.631242037 1.812366605 0.049359232 0.076315492 0.050640557 0.994572878
1403638213945096960 -5.336232185 -1.630235076 1.805463433 0.048929937 0.080012262 0.047227420 0.994471431
1403638213995097088 -5.236464500 -1.625065446 1.800751209 0.049179111 0.079794116 0.048612539 0.994409978
1403638214045096960 -5.134799957 -1.634756684 1.791084886 0.044292282 0.080741525 0.046395984 0.994668961
1403638214095097088 -5.036320210 -1.636729956 1.784646511 0.038488582 0.080832452 0.045582388 0.994940698
1403638214145096960 -4.943380833 -1.646343589 1.780215621 0.032875016 0.080066584 0.044919219 0.995234072
1403638214195097088 -4.843904018 -1.647741318 1.769643784 0.026475335 0.078727685 0.044406075 0.995554686
1403638214245096960 -4.743711948 -1.648456693 1.759335637 0.022336250 0.076931924 0.044088598 0.995810568
1403638214295097088 -4.659923077 -1.650092959 1.761529207 0.018244356 0.076243117 0.044927653 0.995909452
1403638214345096960 -4.556662083 -1.665578127 1.754063606 0.013418810 0.073562779 0.042754881 0.996283352
1403638214395097088 -4.474632263 -1.666914225 1.757246494 0.010893554 0.072201230 0.041825008 0.996453166
1403638214445096960 -4.382039070 -1.676214576 1.754889250 0.010317408 0.071191117 0.039684925 0.996619582
1403638214495097088 -4.289218426 -1.675670505 1.752820849 0.014413699 0.069274180 0.037680384 0.996781588
1403638214545096960 -4.222209930 -1.673667073 1.758317590 0.020558050 0.070371442 0.036896728 0.996626198
1403638214595097088 -4.156597137 -1.692706704 1.758065462 0.024718678 0.071078598 0.033243880 0.996610105
1403638214645096960 -4.089640617 -1.679856420 1.782878876 0.031141391 0.071577139 0.032260813 0.996426702
1403638214695097088 -3.983900785 -1.667393804 1.802976370 0.037292104 0.069545016 0.030373365 0.996418715
1403638214745096960 -3.910839081 -1.655152917 1.839335203 0.043417297 0.070276983 0.028336741 0.996179223
1403638214795097088 -3.808709860 -1.647186518 1.861255884 0.046746850 0.068549924 0.026083777 0.996210456
1403638214845096960 -3.737824202 -1.626862764 1.875487566 0.051862828 0.069393411 0.025379753 0.995917022
1403638214895097088 -3.639126301 -1.631183028 1.860949397 0.054252077 0.067595318 0.026131660 0.995893955
1403638214945096960 -3.553902149 -1.626922369 1.893370628 0.055979613 0.067585915 0.026285943 0.995794892
1403638214995097088 -3.427257299 -1.627307415 1.878359556 0.056463484 0.063807786 0.025214242 0.996044517
1403638215045096960 -3.317392588 -1.615336657 1.884382486 0.057458337 0.061419152 0.025827553 0.996122062
1403638215095097088 -3.247538090 -1.607127905 1.893812656 0.056700628 0.062529027 0.022860786 0.996168911
1403638215145096960 -3.159936905 -1.589060664 1.908802748 0.057021413 0.062447108 0.022674017 0.996160030
1403638215195097088 -3.074018240 -1.591934681 1.907786369 0.053781893 0.062487204 0.021803934 0.996357083
1403638215245096960 -2.982390165 -1.585289955 1.918057680 0.051180985 0.062327515 0.020286638 0.996536076
1403638215295097088 -2.883028507 -1.566277266 1.928996801 0.049927693 0.062780194 0.018804988 0.996600330
1403638215345096960 -2.800096273 -1.550773025 1.945490360 0.048991781 0.064100422 0.016014729 0.996611476
1403638215395097088 -2.739524364 -1.528508306 1.962069035 0.049171705 0.067189686 0.012581287 0.996448398
1403638215445096960 -2.670748472 -1.548555732 1.950600982 0.046780106 0.068782866 0.007555595 0.996505558
1403638215495097088 -2.593308449 -1.518956780 1.960026503 0.048461344 0.070241705 0.008239025 0.996318042
1403638215545096960 -2.499686956 -1.501582623 1.990210891 0.048524674 0.068426512 0.006703039 0.996452808
1403638215595097088 -2.406721592 -1.491830707 1.974977016 0.051702771 0.067353316 0.005899255 0.996371210
1403638215645096960 -2.359107971 -1.501192331 1.963756800 0.052160416 0.068821535 0.006263111 0.996244729
1403638215695097088 -2.267247438 -1.469170809 1.980722785 0.054538146 0.066725597 0.009677944 0.996232688
1403638215745096960 -2.233855724 -1.465491414 2.005081415 0.055988118 0.069327697 0.013535126 0.995929599
1403638215795097088 -2.121672869 -1.460544467 2.007532358 0.055575673 0.068683520 0.014842300 0.995978713
1403638215845096960 -2.063903332 -1.466804028 2.012637615 0.053811513 0.070806697 0.016224895 0.995905340
1403638215895097088 -1.989309549 -1.453671217 2.013334513 0.053857118 0.073187888 0.016402936 0.995727837
1403638215945096960 -1.937571049 -1.427024126 2.049888134 0.055945981 0.077433430 0.017152483 0.995278776
1403638215995097088 -1.859991074 -1.413475037 2.039854288 0.056716762 0.078088343 0.019832551 0.995134175
1403638216045096960 -1.778298855 -1.406614900 2.036322117 0.056224655 0.078782015 0.022352846 0.995054007
1403638216095097088 -1.728917599 -1.378334522 2.070071220 0.057529680 0.083189689 0.020469652 0.994661152
1403638216145096960 -1.665974498 -1.364594579 2.085380077 0.057189453 0.084237188 0.020667352 0.994588494
1403638216195097088 -1.606658816 -1.351048112 2.087366104 0.057971720 0.086197056 0.019014288 0.994408250
1403638216245096960 -1.539531231 -1.350671411 2.077752352 0.059104390 0.087788515 0.018501213 0.994212031
1403638216295097088 -1.469886541 -1.341071963 2.068849325 0.059354555 0.088408470 0.020225186 0.994108617
1403638216345096960 -1.413591623 -1.355973959 2.027887821 0.059435654 0.088531695 0.019572331 0.994105875
1403638216395097088 -1.400056481 -1.323464870 2.059928179 0.062543958 0.092426069 0.017476920 0.993599653
1403638216445096960 -1.332049608 -1.332859039 2.026924133 0.062272578 0.092665121 0.020904871 0.993528187
1403638216495097088 -1.228691101 -1.357956409 2.005543470 0.060755141 0.089447327 0.019125935 0.993952811
1403638216545096960 -1.174971938 -1.356812000 1.983519673 0.059717558 0.090174638 0.018873751 0.993954778
1403638216595097088 -1.126972198 -1.342174768 1.999036551 0.059604418 0.091768116 0.017924599 0.993833303
1403638216645096960 -1.063452959 -1.336010695 1.977368474 0.057851207 0.091905616 0.016778121 0.993944228
1403638216695097088 -1.027614117 -1.313819170 1.981278181 0.057055302 0.093976982 0.014972136 0.993825376
1403638216745096960 -0.989504039 -1.301787376 1.985589385 0.056125794 0.095035054 0.013033653 0.993804991
1403638216795097088 -0.932422996 -1.300124884 1.962718487 0.057686441 0.096200004 0.010964642 0.993628502
1403638216845096960 -0.876973867 -1.275237679 1.970181227 0.062075749 0.098545402 0.011490898 0.993128061
1403638216895097088 -0.835842371 -1.262888432 1.967227459 0.064284332 0.102873065 0.011906490 0.992543638
1403638216945096960 -0.777657509 -1.257775545 1.932608008 0.064899221 0.105344377 0.014949294 0.992203176
1403638216995097088 -0.738487840 -1.239503026 1.956614971 0.065211341 0.110975698 0.018598318 0.991506934
1403638217045096960 -0.692653060 -1.220008254 1.938097358 0.063832119 0.115995146 0.024189379 0.990901351
1403638217095097088 -0.659615755 -1.188079357 1.955169678 0.062805966 0.123177610 0.029507378 0.989955604
1403638217145096960 -0.592774510 -1.181358576 1.922697783 0.059392855 0.127991349 0.034700342 0.989386976
1403638217195097088 -0.554786682 -1.165061235 1.916498303 0.056947269 0.134585589 0.038491312 0.988515139
1403638217245096960 -0.521696329 -1.142131686 1.912929773 0.055225998 0.141228080 0.040049668 0.987623751
1403638217295097088 -0.468874753 -1.126853585 1.890107155 0.053981762 0.144881785 0.043458279 0.987019062
1403638217345096960 -0.440571606 -1.109072447 1.894253612 0.052266866 0.149898842 0.043433636 0.986363053
1403638217395097088 -0.398300290 -1.095767856 1.882706046 0.050479755 0.153176829 0.045274977 0.985869586
1403638217445096960 -0.375539005 -1.087189198 1.875011921 0.049603492 0.157112196 0.045120660 0.985301673
1403638217495097088 -0.335017741 -1.070038319 1.862801075 0.048850436 0.159706861 0.044814400 0.984936059
1403638217545096960 -0.291544259 -1.062660336 1.844960690 0.047276080 0.162086815 0.042979509 0.984705806
1403638217595097088 -0.263165534 -1.054735303 1.840493560 0.046176013 0.164429620 0.040297493 0.984483004
1403638217645096960 -0.226751566 -1.048750401 1.817208290 0.045197073 0.166749671 0.036996290 0.984267771
1403638217695097088 -0.201554120 -1.039285660 1.821131229 0.045000669 0.169651628 0.033336211 0.983911574
1403638217745096960 -0.164382398 -1.041947961 1.787651658 0.042959392 0.170588315 0.029443888 0.983965039
1403638217795097088 -0.136535525 -1.038690805 1.778624535 0.041619003 0.171652555 0.025795855 0.983939946
1403638217845096960 -0.114456296 -1.038137674 1.767713785 0.040204655 0.172770232 0.022932338 0.983874083
1403638217895097088 -0.085294604 -1.034679174 1.760749578 0.041266978 0.172534958 0.022692118 0.983876884
1403638217945096960 -0.069764316 -1.040656686 1.745237827 0.042740040 0.173179045 0.019392261 0.983771443
1403638217995097088 -0.048138201 -1.036143541 1.730876327 0.045139894 0.172176242 0.019611042 0.983835936
1403638218045096960 -0.030680776 -1.039005280 1.723063946 0.046146329 0.171632394 0.018065356 0.983913839
1403638218095097088 -0.019309700 -1.039371252 1.714886785 0.047326192 0.171743155 0.017247710 0.983853161
1403638218145096960 -0.002020001 -1.029714704 1.711565495 0.049438819 0.170298040 0.018298088 0.983981490
1403638218195097088 -0.004133165 -1.024271965 1.703587413 0.051387575 0.170498863 0.017070414 0.983868897
1403638218245096960 0.015400112 -1.033552647 1.674392343 0.053691514 0.168864891 0.017708356 0.984016418
1403638218295097088 0.034624100 -1.031224728 1.658071756 0.056857243 0.166924953 0.018239645 0.984159827
1403638218345096960 0.039955139 -1.029106140 1.654676080 0.060336150 0.164852530 0.020766411 0.984251976
1403638218395097088 0.044297576 -1.024322391 1.643635631 0.061440762 0.162613511 0.022890132 0.984508991
1403638218445096960 0.053791761 -1.019529223 1.631693602 0.062078428 0.160181120 0.025557538 0.984802067
1403638218495097088 0.038642019 -1.011775255 1.630512714 0.062229507 0.159813017 0.027020579 0.984813273
1403638218545096960 0.044130653 -1.015723586 1.607899547 0.061066680 0.158721372 0.027330274 0.985054016
1403638218595097088 0.049378812 -1.020312190 1.594042659 0.060166307 0.157303452 0.028936256 0.985291004
1403638218645096960 0.042357206 -1.022279501 1.579208374 0.057767425 0.156703562 0.029786417 0.985504806
1403638218695097088 0.034525722 -1.018360972 1.571020842 0.054388888 0.156654909 0.032208569 0.985628605
1403638218745096960 0.033236682 -1.022935152 1.551954746 0.049483553 0.158511147 0.032906752 0.985567212
1403638218795097088 0.027372479 -1.026164889 1.535957456 0.045427307 0.161684394 0.035748195 0.985148013
1403638218845096960 0.020367891 -1.021418929 1.527470231 0.042499028 0.165638387 0.037300572 0.984564066
1403638218895097088 0.013305485 -1.012304187 1.520620346 0.041699778 0.168824658 0.040445145 0.983932734
1403638218945096960 0.006574303 -1.014848113 1.502133727 0.041401330 0.169021219 0.048841722 0.983530521
1403638218995097088 -0.002902418 -1.011031032 1.493248940 0.042677827 0.169051707 0.058208287 0.982960820
1403638219045096960 -0.005804658 -1.009249091 1.480364561 0.044258613 0.168485850 0.066227280 0.982480347
1403638219095097088 -0.019649565 -1.000250101 1.476421237 0.046877574 0.169271260 0.071888514 0.981825709
1403638219145096960 -0.025018036 -0.996024847 1.465226889 0.048030648 0.170906931 0.073611617 0.981358886
1403638219195097088 -0.025988787 -0.986906826 1.459544182 0.050388228 0.173229009 0.071581982 0.980983555
1403638219245096960 -0.031867146 -0.975064516 1.451018333 0.054717585 0.176696256 0.067247897 0.980439782
1403638219295097088 -0.039080322 -0.967730761 1.437128305 0.059339244 0.179543361 0.063669249 0.979892492
1403638219345096960 -0.045529544 -0.959113598 1.435077548 0.064244613 0.182449788 0.058863338 0.979346633
1403638219395097088 -0.046111345 -0.956034601 1.420095563 0.070901521 0.183436871 0.057218760 0.978800237
1403638219445096960 -0.058659911 -0.942695022 1.409143448 0.076503940 0.185419858 0.054022383 0.978186190
1403638219495097088 -0.068759620 -0.939216018 1.396086216 0.079305910 0.186472937 0.052357230 0.977853298
1403638219545096960 -0.079180896 -0.933991790 1.387628317 0.079572335 0.186587811 0.052693821 0.977791667
1403638219595097088 -0.084795803 -0.929014504 1.364548206 0.078389980 0.185335889 0.054961860 0.978000402
1403638219645096960 -0.092984200 -0.923796773 1.346386790 0.076021217 0.184268937 0.057230387 0.978258848
1403638219695097088 -0.106020868 -0.918541610 1.327532053 0.074732155 0.182423785 0.061143916 0.978467226
1403638219745096960 -0.117706805 -0.911352277 1.308835030 0.071791492 0.180989519 0.064475410 0.978739858
1403638219795097088 -0.130262643 -0.904015362 1.285199404 0.069568478 0.178880185 0.069629818 0.978935003
1403638219845096960 -0.146091610 -0.894062042 1.266383052 0.066792190 0.177107513 0.074527547 0.979090095
1403638219895097088 -0.158177227 -0.882817566 1.241441011 0.064914137 0.175018340 0.079422079 0.979207277
1403638219945096960 -0.160751700 -0.865761518 1.216010809 0.063252270 0.172780812 0.084013768 0.979330182
1403638219995097088 -0.168602765 -0.850517869 1.195245981 0.061272752 0.171076640 0.087503195 0.979449630
1403638220045096960 -0.176737219 -0.833937645 1.171452880 0.058983482 0.170180693 0.090085395 0.979512155
1403638220095097088 -0.179973990 -0.811592400 1.153377295 0.057691246 0.169929788 0.090621114 0.979583263
1403638220145096960 -0.180945843 -0.798495889 1.129687428 0.055094596 0.170783803 0.087640472 0.979855418
1403638220195097088 -0.189796805 -0.777440846 1.102589130 0.053315595 0.173721552 0.081776813 0.979944289
1403638220245096960 -0.192338705 -0.762364686 1.082355738 0.051509336 0.177778572 0.072485685 0.980044603
1403638220295097088 -0.193092674 -0.750562608 1.054702520 0.048169717 0.180926338 0.065086097 0.980157733
1403638220345096960 -0.189745545 -0.738689840 1.023588061 0.047204860 0.182989731 0.059513591 0.980175793
1403638220395097088 -0.195654899 -0.724634528 0.998889685 0.046599139 0.185140952 0.055477809 0.980037510
1403638220445096960 -0.195864320 -0.722923934 0.969573140 0.045632485 0.185659960 0.053888537 0.980073512
1403638220495097088 -0.197141409 -0.706883609 0.942224741 0.046020191 0.186747983 0.051862173 0.979957998
1403638220545096960 -0.199332863 -0.708222866 0.915525198 0.046374787 0.186793923 0.052531835 0.979896843
1403638220595097088 -0.200779676 -0.703986347 0.889210939 0.046283316 0.187625736 0.051907644 0.979775488
1403638220645096960 -0.210870594 -0.697042525 0.864924788 0.046560615 0.188691989 0.052002087 0.979552567
1403638220695097088 -0.209342778 -0.688168466 0.838019609 0.047000196 0.189070240 0.052244894 0.979445696
1403638220745096960 -0.206891567 -0.678797126 0.811189651 0.046602711 0.188956931 0.053482048 0.979419768
1403638220795097088 -0.219654471 -0.663030863 0.789371610 0.046970703 0.189616561 0.053818073 0.979256272
1403638220845096960 -0.219766080 -0.655975640 0.765177667 0.047372993 0.189456090 0.055222567 0.979189813
1403638220895097088 -0.226768553 -0.644465744 0.744370818 0.046569217 0.190362260 0.055123828 0.979058146
1403638220945096960 -0.241421029 -0.620363891 0.721088469 0.046285301 0.190541744 0.056723293 0.978945315
1403638220995097088 -0.245825320 -0.605181456 0.695606291 0.045270868 0.190710112 0.056911271 0.978949070
1403638221045096960 -0.248836443 -0.589454889 0.675100088 0.044981886 0.190863416 0.057392687 0.978904426
1403638221095097088 -0.262699783 -0.568912327 0.658899069 0.044589236 0.191710711 0.057635158 0.978742540
1403638221145096960 -0.257088035 -0.552269042 0.637861848 0.043698695 0.191448748 0.057825312 0.978822768
1403638221195097088 -0.270882726 -0.537269175 0.616615057 0.042162564 0.191672593 0.058390878 0.978812754
1403638221245096960 -0.277257800 -0.527135730 0.599732995 0.040834267 0.191717565 0.059257116 0.978808224
1403638221295097088 -0.290553510 -0.517490923 0.576916277 0.039533373 0.191305175 0.060602311 0.978859961
1403638221345096960 -0.300304323 -0.502842486 0.556044042 0.038522810 0.191264361 0.061757799 0.978836000
1403638221395097088 -0.301943958 -0.493087202 0.540905893 0.038159300 0.190640047 0.064019293 0.978826702
1403638221445096960 -0.302364975 -0.484786302 0.513742685 0.037665129 0.189876631 0.065739624 0.978880227
1403638221495097088 -0.326873124 -0.474147826 0.499254465 0.037794277 0.190383226 0.066642478 0.978715777
1403638221545096960 -0.325524092 -0.469149977 0.470174730 0.037693754 0.189445928 0.068477973 0.978774846
1403638221595097088 -0.333237529 -0.452533871 0.454284966 0.039051082 0.189728826 0.069206752 0.978615582
1403638221645096960 -0.339060664 -0.442319751 0.441911876 0.039787691 0.189873815 0.069220446 0.978556812
1403638221695097088 -0.349989653 -0.430661976 0.426741958 0.042123266 0.189756259 0.070046283 0.978423059
1403638221745096960 -0.353541762 -0.419017524 0.411521494 0.044567171 0.189262569 0.071357131 0.978315711
1403638221795097088 -0.360730469 -0.408742368 0.395483524 0.045928661 0.188755676 0.071834445 0.978315711
1403638221845096960 -0.365580171 -0.398048908 0.375188291 0.046271369 0.188624486 0.071627446 0.978340030
1403638221895097088 -0.365647465 -0.390638828 0.360421240 0.047686443 0.189067438 0.069210380 0.978360534
1403638221945096960 -0.376039952 -0.388582706 0.339239448 0.048071675 0.190139905 0.065998361 0.978355825
1403638221995097088 -0.380039960 -0.379193038 0.328412652 0.048731085 0.190795496 0.064252138 0.978311837
1403638222045096960 -0.375849664 -0.374033123 0.298991531 0.047687467 0.191055879 0.062422708 0.978430867
1403638222095097088 -0.385631114 -0.373648196 0.280550718 0.045319006 0.191966012 0.060651228 0.978476703
1403638222145096960 -0.392625332 -0.374419779 0.256533414 0.041659959 0.191942841 0.060971342 0.978623927
1403638222195097088 -0.401337147 -0.366005570 0.241675973 0.038433511 0.192324698 0.060449392 0.978713393
1403638222245096960 -0.402914017 -0.360801190 0.220052034 0.035305124 0.191815779 0.061723933 0.978851557
1403638222295097088 -0.402417153 -0.350706935 0.208972186 0.032413747 0.191534162 0.062475786 0.978959024
1403638222345096960 -0.404603183 -0.345002860 0.188858852 0.029312311 0.191039965 0.063344002 0.979097605
1403638222395097088 -0.410369009 -0.337527990 0.174110517 0.027043428 0.190890431 0.064052574 0.979145944
1403638222445096960 -0.420154124 -0.329956800 0.162230089 0.024384558 0.190958828 0.064475454 0.979174674
1403638222495097088 -0.429860085 -0.315061748 0.156605348 0.023301490 0.191332400 0.064136446 0.979150355
1403638222545096960 -0.431120217 -0.310905993 0.147952586 0.024960268 0.190929621 0.064564385 0.979160011
1403638222595097088 -0.431550980 -0.304895610 0.135964975 0.029335478 0.190925270 0.063525215 0.979107499
1403638222645096960 -0.444840968 -0.290089011 0.127600312 0.035075199 0.191273004 0.063841894 0.978830218
1403638222695097088 -0.435095400 -0.277471811 0.116483219 0.039131485 0.190400660 0.064390011 0.978810608
1403638222745096960 -0.442512900 -0.273008585 0.110100664 0.041333191 0.191169724 0.063478462 0.978629768
1403638222795097088 -0.449146181 -0.252272189 0.113718286 0.043431383 0.191473871 0.063052602 0.978506982
1403638222845096960 -0.453027815 -0.247681662 0.097684681 0.045899801 0.191648483 0.062322423 0.978406847
1403638222895097088 -0.460102886 -0.233378604 0.101326957 0.052749384 0.192443788 0.060327139 0.978030443
1403638222945096960 -0.460259497 -0.224751055 0.097983830 0.058919348 0.191841722 0.060486905 0.977786601
1403638222995097088 -0.467013687 -0.212470427 0.092182621 0.060880832 0.191717848 0.060822438 0.977669895
1403638223045096960 -0.477136821 -0.193934396 0.085785076 0.060025740 0.191787913 0.060636826 0.977720559
1403638223095097088 -0.470364153 -0.188291758 0.067595646 0.056030616 0.191139787 0.060963120 0.978064239
1403638223145096960 -0.478958994 -0.183500841 0.064501084 0.049526419 0.191456348 0.061211288 0.978337765
1403638223195097088 -0.489377171 -0.176046401 0.051025733 0.040511083 0.190212712 0.064575724 0.978778780
1403638223245096960 -0.496133536 -0.166378841 0.041798383 0.032401130 0.188413695 0.069387518 0.979099512
1403638223295097088 -0.505013704 -0.156568304 0.032152101 0.027452352 0.187578335 0.072000958 0.979222417
1403638223345096960 -0.511488736 -0.144903317 0.027210534 0.029135181 0.187457144 0.073077239 0.979117274
1403638223395097088 -0.515147090 -0.140644088 0.019814879 0.031215534 0.186545298 0.075622804 0.979034007
1403638223445096960 -0.513935566 -0.135397255 0.010653004 0.035671070 0.184357420 0.080793574 0.978883207
1403638223495097088 -0.520742774 -0.133070305 -0.001543090 0.040298745 0.182078525 0.086796664 0.978616238
1403638223545096960 -0.518980205 -0.129066110 -0.003953427 0.043290246 0.180666357 0.089870334 0.978472769
1403638223595097088 -0.520163298 -0.120662443 -0.018706843 0.044480659 0.181488618 0.087799609 0.978455186
1403638223645096960 -0.517111957 -0.109246843 -0.021027520 0.045082372 0.184163466 0.081569590 0.978467047
1403638223695097088 -0.512886167 -0.092820063 -0.018083885 0.044920970 0.186453119 0.075844176 0.978501439
1403638223745096960 -0.510901153 -0.085575387 -0.027244419 0.043686405 0.189530194 0.069210447 0.978457868
1403638223795097088 -0.503977001 -0.076447926 -0.036418810 0.042283785 0.191345617 0.064247966 0.978504539
1403638223845096960 -0.505152583 -0.065761641 -0.043528005 0.041579537 0.192838058 0.060400963 0.978486776
1403638223895097088 -0.506147265 -0.058834121 -0.055074468 0.040614177 0.193958566 0.057748806 0.978465974
1403638223945096960 -0.504307628 -0.046443582 -0.056740433 0.040541954 0.195020869 0.054770440 0.978429019
1403638223995097088 -0.501939178 -0.032427322 -0.052389652 0.039656196 0.195780709 0.053298254 0.978394926
1403638224045096960 -0.497640878 -0.024240009 -0.062982753 0.036607750 0.195409253 0.053159967 0.978595495
1403638224095097088 -0.502237320 -0.011441770 -0.070380330 0.032598600 0.194791660 0.054962542 0.978760779
1403638224145096960 -0.514853716 -0.005677863 -0.075325966 0.026498191 0.194357663 0.056374595 0.978950858
1403638224195097088 -0.516681015 0.005211831 -0.077742502 0.021368204 0.193781957 0.058401696 0.979071558
1403638224245096960 -0.517605364 0.015322315 -0.077868283 0.020911636 0.193395257 0.059236694 0.979107738
1403638224295097088 -0.518979609 0.022421494 -0.078270748 0.022625493 0.193423912 0.058772586 0.979091942
1403638224345096960 -0.520504177 0.028426681 -0.078330427 0.028180607 0.193605378 0.058487508 0.978929043
1403638224395097088 -0.522968531 0.033787124 -0.077812701 0.033737175 0.192850307 0.061176330 0.978737950
1403638224445096960 -0.525890768 0.038968168 -0.075557426 0.039542455 0.191406131 0.064895108 0.978564620
1403638224495097088 -0.527948260 0.044142410 -0.072736114 0.047129817 0.191012055 0.066017084 0.978230536
1403638224545096960 -0.530276358 0.049596738 -0.070872173 0.052128017 0.191780999 0.064133033 0.977951765
1403638224595097088 -0.532805502 0.055692255 -0.068836614 0.052608825 0.191892743 0.063457586 0.977948189
1403638224645096960 -0.535897851 0.062560290 -0.068187118 0.047893394 0.192333549 0.062690087 0.978153348
1403638224695097088 -0.538565218 0.070187047 -0.065774605 0.039396986 0.191985548 0.063670106 0.978537440
1403638224745096960 -0.541771531 0.077216588 -0.065153807 0.030084452 0.191283658 0.065152191 0.978907943
1403638224795097088 -0.544782519 0.082178660 -0.063564181 0.024204934 0.191318139 0.065269418 0.979056358
1403638224845096960 -0.547514081 0.084759489 -0.061619714 0.025231695 0.190777972 0.066008702 0.979086280
1403638224895097088 -0.550449491 0.084562741 -0.059233382 0.031176632 0.189190999 0.069511816 0.978980541
1403638224945096960 -0.553372741 0.083339840 -0.057377562 0.038517311 0.187467173 0.073053159 0.978792965
1403638224995097088 -0.555913091 0.081200443 -0.054580122 0.046004791 0.185706258 0.076619297 0.978532672
1403638225045096960 -0.557640910 0.079046302 -0.053157747 0.050298579 0.184634969 0.078101665 0.978406906
1403638225095097088 -0.558384418 0.077346876 -0.051457644 0.052601863 0.185064897 0.076319963 0.978345156
1403638225145096960 -0.558595300 0.075576521 -0.050722912 0.051310748 0.186019957 0.072804227 0.978500545
1403638225195097088 -0.558708310 0.074135244 -0.050562859 0.046680376 0.186844766 0.069621205 0.978806853
1403638225245096960 -0.558851838 0.072605051 -0.050748169 0.039903987 0.187230587 0.067544371 0.979178309
1403638225295097088 -0.558500528 0.070492797 -0.050414309 0.033606835 0.187762082 0.065939821 0.979422271
1403638225345096960 -0.557951927 0.066982731 -0.051109463 0.033235490 0.188163370 0.064508021 0.979453266
1403638225395097088 -0.557072699 0.064086214 -0.049979225 0.034882165 0.188446268 0.062805317 0.979452252
1403638225445096960 -0.556942821 0.062067702 -0.048064038 0.040358696 0.189404443 0.061374918 0.979147732
1403638225495097088 -0.555560172 0.061421290 -0.044375047 0.048887309 0.189997047 0.059493132 0.978760302
1403638225545096960 -0.554894924 0.062818378 -0.040159926 0.057929277 0.191207781 0.057125136 0.978172004
1403638225595097088 -0.554732502 0.065906227 -0.035598680 0.066956237 0.192208946 0.055038899 0.977518976
1403638225645096960 -0.555283666 0.070834443 -0.032002166 0.075160787 0.192296565 0.054036234 0.976961076
1403638225695097088 -0.555935204 0.079829812 -0.027285159 0.075503066 0.192226753 0.053454403 0.976980448
1403638225745096960 -0.558573365 0.092010953 -0.020958453 0.071424440 0.192384973 0.052954540 0.977283180
1403638225795097088 -0.562208652 0.106293254 -0.019813880 0.063313104 0.191579327 0.055060197 0.977883995
1403638225845096960 -0.567242801 0.123775825 -0.014601365 0.052025337 0.191298708 0.055921994 0.978555501
1403638225895097088 -0.570387483 0.142128289 -0.007811621 0.042009059 0.190680832 0.057722121 0.979052722
1403638225945096960 -0.575042486 0.160346448 -0.002384245 0.034526322 0.189831004 0.059016619 0.979433060
1403638225995097088 -0.579534173 0.178303912 0.004155442 0.027297264 0.188770786 0.062664330 0.979639530
1403638226045096960 -0.584877670 0.188542888 0.008748725 0.019251123 0.184818909 0.064884156 0.980439365
1403638226095097088 -0.613679826 0.080618367 0.086586982 0.020257507 0.179950684 0.082502738 0.980000377
1403638226145096960 -0.671695590 -0.027549881 0.156692579 0.014665301 0.181127489 0.085738070 0.979605377
1403638226195097088 -0.679118693 -0.029416036 0.114574850 0.006283381 0.180963323 0.081869431 0.980056226
1403638226245096960 -0.754741490 -0.169977784 0.118825629 -0.003111791 0.195779920 0.063183740 0.978605330
1403638226295097088 -0.910653651 -0.356061101 0.129491448 0.001724380 0.201241314 0.072686531 0.976839602
1403638226345096960 -1.073825717 -0.601655006 0.235011563 -0.014392019 0.208615452 0.071697526 0.975259960
1403638226395097088 -1.158968091 -0.650858581 0.281991333 -0.016258566 0.211223885 0.074045628 0.974493384
1403638226445096960 -1.183297157 -0.774592876 0.354050636 -0.020820457 0.215842396 0.074152194 0.973385811
1403638226495097088 -1.152065158 -0.719344199 0.319831729 -0.018379146 0.213611081 0.074540213 0.973897457
1403638226545096960 -1.201868176 -0.791381836 0.356909871 -0.021129111 0.216410056 0.074264146 0.973244607
1403638226595097088 -1.189073682 -0.782611370 0.334830582 -0.021424750 0.215979889 0.074171148 0.973340750
1403638226645096960 -1.213577986 -0.807271421 0.366601467 -0.021635521 0.216664165 0.075179994 0.973106623
1403638226695097088 -1.201939464 -0.807457805 0.357006460 -0.022947004 0.217166781 0.073351756 0.973104060
1403638226745096960 -1.187595248 -0.787584841 0.346233338 -0.021404341 0.215160534 0.075741045 0.973401785
1403638226795097088 -1.244174480 -0.861462176 0.384313703 -0.025337456 0.219629213 0.073169753 0.972505629
1403638226845096960 -1.246009469 -0.865280986 0.380353183 -0.025104323 0.218331635 0.075276889 0.972643018
1403638226895097088 -1.229794502 -0.836871922 0.369801223 -0.024378102 0.218484879 0.073330410 0.972775817
1403638226945096960 -1.237540483 -0.857374072 0.380877137 -0.024853084 0.218789816 0.074070297 0.972639143
1403638226995097088 -1.257140040 -0.877640426 0.380822599 -0.026005454 0.219055131 0.074741647 0.972497940
1403638227045096960 -1.222002387 -0.828587472 0.368925452 -0.023887595 0.218279928 0.073298052 0.972836375
1403638227095097088 -1.215874910 -0.831820786 0.360310912 -0.023558155 0.216679558 0.075603835 0.973025680
1403638227145096960 -1.190085530 -0.794586122 0.348936141 -0.022168985 0.216469616 0.073761791 0.973246455
1403638227195097088 -1.198738694 -0.796317518 0.351046145 -0.021825368 0.216009438 0.074968927 0.973264217
1403638227245096960 -1.198625803 -0.796366394 0.351626188 -0.022260411 0.216465339 0.074124418 0.973217785
1403638227295097088 -1.198716521 -0.796524107 0.352052689 -0.021960473 0.216483757 0.074416563 0.973198175
1403638227345096960 -1.198670506 -0.796272397 0.350986600 -0.021950858 0.216104433 0.074700125 0.973260999
1403638227395097088 -1.198620558 -0.796215653 0.351165414 -0.022119032 0.216547027 0.073991746 0.973212898
1403638227445096960 -1.198687196 -0.796262205 0.350840151 -0.021994960 0.216021910 0.074756131 0.973273993
1403638227495097088 -1.198643804 -0.796200931 0.351123929 -0.022073114 0.216455624 0.074094117 0.973226488
1403638227545096960 -1.198660493 -0.796254933 0.351081669 -0.022034999 0.216246814 0.074459553 0.973245919
1403638227595097088 -1.198650599 -0.796216130 0.350900084 -0.022019191 0.216190904 0.074470833 0.973257780
1403638227645096960 -1.198605895 -0.796220899 0.351132512 -0.022069462 0.216452554 0.074116945 0.973225534
1403638227695097088 -1.198612928 -0.796248376 0.350926369 -0.021965696 0.216111809 0.074667290 0.973261535
1403638227745096960 -1.198668718 -0.796256423 0.351112306 -0.022078333 0.216475502 0.074213929 0.973212838
1403638227795097088 -1.198660493 -0.796237111 0.350851655 -0.021954736 0.216179103 0.074470557 0.973261893
1403638227845096960 -1.198617220 -0.796236575 0.351165056 -0.022119273 0.216306642 0.074174352 0.973252475
1403638227895097088 -1.198658586 -0.796234608 0.351018041 -0.022033785 0.216264084 0.074258797 0.973257422
1403638227945096960 -1.198687792 -0.796305895 0.351215363 -0.022102850 0.216271505 0.074381098 0.973244846
1403638227995097088 -1.198621392 -0.796237588 0.351148635 -0.022028187 0.216340885 0.074222527 0.973243237
1403638228045096960 -1.198685408 -0.796368718 0.351396084 -0.022079905 0.216336355 0.074487120 0.973222852
1403638228095097088 -1.198646665 -0.796340764 0.351512730 -0.022091080 0.216456577 0.074277036 0.973211944
1403638228145096960 -1.198688507 -0.796320438 0.351443857 -0.022032639 0.216325790 0.074404188 0.973232627
1403638228195097088 -1.198652506 -0.796345234 0.351347744 -0.022052553 0.216434777 0.074294738 0.973216295
1403638228245096960 -1.198661685 -0.796341002 0.351378679 -0.022066159 0.216390640 0.074317843 0.973224044
1403638228295097088 -1.198692083 -0.796349823 0.351382136 -0.022050997 0.216401994 0.074435174 0.973212898
1403638228345096960 -1.198662519 -0.796337545 0.351412982 -0.022016436 0.216407657 0.074338235 0.973219872
1403638228395097088 -1.198667169 -0.796373606 0.351340175 -0.022118602 0.216317326 0.074527062 0.973223150
1403638228445096960 -1.198634386 -0.796382725 0.351320595 -0.022206629 0.216398105 0.074312173 0.973219633
1403638228495097088 -1.198698997 -0.796362400 0.351316929 -0.022050746 0.216335580 0.074366949 0.973232865
1403638228545096960 -1.198689222 -0.796291351 0.351333916 -0.022032686 0.216335952 0.074308909 0.973237634
1403638228595097088 -1.198716164 -0.796365798 0.351364553 -0.022129809 0.216286525 0.074402720 0.973239243
1403638228645096960 -1.198637724 -0.796333730 0.351358026 -0.022132827 0.216305688 0.074414656 0.973234057
1403638228695097088 -1.198757887 -0.796344221 0.351239026 -0.021977946 0.216312483 0.074448936 0.973233402
1403638228745096960 -1.198654652 -0.796331346 0.351401210 -0.022123206 0.216317713 0.074356198 0.973236024
1403638228795097088 -1.198647261 -0.796290100 0.351417333 -0.022141766 0.216358855 0.074342161 0.973227561
1403638228845096960 -1.198684573 -0.796276212 0.351360142 -0.022039663 0.216314718 0.074317902 0.973241568
================================================
FILE: Examples/Stereo/euroc_old/CameraTrajectory_MH05.txt
================================================
1403638518077829376 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 0.000000000 1.000000000
1403638518127829504 0.000028363 -0.000022944 -0.000027469 0.000009761 -0.000057429 0.000131375 1.000000000
1403638518177829376 0.000030309 0.000000757 -0.000020274 0.000019648 -0.000031219 0.000138445 1.000000000
1403638518227829504 -0.000000002 -0.000027886 -0.000063784 0.000013436 0.000022652 0.000016997 1.000000000
1403638518277829376 0.000070609 -0.000028296 0.000003605 0.000034206 -0.000108288 0.000253401 0.999999940
1403638518327829504 -0.000017578 -0.000030835 0.000006141 -0.000043817 0.000049532 -0.000089191 1.000000000
1403638518377829376 -0.000033692 0.000010726 -0.000016108 0.000023261 0.000039642 -0.000018318 1.000000000
1403638518427829504 0.000010011 -0.000003722 0.000098251 0.000009397 0.000020459 0.000064441 1.000000000
1403638518477829376 0.000008604 -0.000024322 0.000037613 -0.000025181 -0.000028884 0.000101511 1.000000000
1403638518527829504 0.000024296 -0.000022873 0.000004232 -0.000042335 0.000018911 0.000053078 1.000000000
1403638518577829376 -0.000002521 -0.000024476 -0.000075690 -0.000015986 0.000050243 0.000093556 1.000000000
1403638518627829504 0.000029260 -0.000032966 -0.000060921 0.000006504 -0.000006698 0.000142491 1.000000000
1403638518677829376 0.000013286 -0.000052102 -0.000026317 -0.000086587 -0.000002725 0.000063318 1.000000000
1403638518727829504 0.000019488 -0.000001588 0.000028165 -0.000017369 0.000031453 0.000035146 1.000000000
1403638518777829376 0.000026438 -0.000061673 -0.000006338 -0.000112789 -0.000043214 -0.000002102 1.000000000
1403638518827829504 0.000002525 -0.000009602 0.000002454 -0.000050806 0.000010369 0.000037289 1.000000000
1403638518877829376 0.000016021 -0.000028068 -0.000054027 -0.000000549 -0.000016310 0.000068489 1.000000000
1403638518927829504 0.000062624 -0.000026704 0.000049422 0.000025464 -0.000094982 0.000187870 1.000000000
1403638518977829376 0.000059993 0.000003880 0.000005171 0.000021191 -0.000091361 0.000082019 1.000000000
1403638519027829504 0.000067160 -0.000012294 0.000021772 0.000030623 -0.000020987 0.000056440 1.000000000
1403638519077829376 -0.000012043 -0.000028310 -0.000061833 0.000006425 0.000008048 -0.000005324 1.000000000
1403638519127829504 0.000014184 -0.000041007 -0.000109869 -0.000009928 -0.000035538 0.000068234 1.000000000
1403638519177829376 0.000048430 0.000003997 0.000094465 0.000014047 -0.000040986 0.000183371 1.000000000
1403638519227829504 0.000010455 -0.000041097 -0.000047843 -0.000033439 -0.000021685 0.000100468 1.000000000
1403638519277829376 0.000067226 -0.000006671 0.000078359 0.000019341 -0.000011982 0.000092158 1.000000000
1403638519327829504 0.000001059 -0.000043437 -0.000091453 -0.000022303 0.000004705 0.000072818 1.000000000
1403638519377829376 -0.000010666 -0.000038628 -0.000028610 -0.000024683 -0.000016304 0.000076742 1.000000000
1403638519427829504 0.000017227 -0.000019512 0.000050102 -0.000005594 0.000021384 0.000044445 1.000000000
1403638519477829376 -0.000012106 -0.000034162 -0.000042714 -0.000028748 0.000043600 0.000102315 1.000000000
1403638519527829504 0.000026091 -0.000027927 0.000071922 0.000028765 -0.000065550 0.000162014 1.000000000
1403638519577829376 0.000023824 -0.000008085 -0.000003492 0.000016200 -0.000061568 0.000114377 1.000000000
1403638519627829504 0.000019223 -0.000056416 0.000049522 -0.000033474 0.000002877 0.000188959 1.000000000
1403638519677829376 0.000007404 -0.000027039 -0.000058142 -0.000000863 0.000015332 0.000088861 1.000000000
1403638519727829504 -0.000018762 -0.000051479 -0.000022329 -0.000052463 0.000060519 0.000139219 1.000000000
1403638519777829376 0.000001710 -0.000049143 -0.000008856 0.000028093 -0.000009556 0.000075277 1.000000000
1403638519827829504 0.000000625 -0.000052079 0.000002299 -0.000064328 -0.000003210 0.000013545 1.000000000
1403638519877829376 0.000048557 -0.000047968 0.000001021 -0.000064038 -0.000108335 0.000265303 0.999999940
1403638519927829504 0.000036344 -0.000006165 -0.000005052 0.000023695 -0.000066168 0.000199279 0.999999940
1403638519977829376 0.000002042 -0.000015613 -0.000075923 -0.000024596 -0.000021081 0.000070229 1.000000000
1403638520027829504 0.000032362 -0.000045304 0.000003911 -0.000006769 -0.000033808 0.000102946 1.000000000
1403638520077829376 0.000031867 -0.000003646 -0.000045452 0.000017505 -0.000000852 0.000033064 1.000000000
1403638520127829504 -0.000003798 0.000008010 0.000029100 0.000028931 0.000051235 0.000000141 1.000000000
1403638520177829376 -0.000006851 0.000006441 -0.000018039 0.000013749 0.000003402 0.000008693 1.000000000
1403638520227829504 -0.000019545 -0.000013764 -0.000064851 0.000039119 0.000021406 0.000083321 1.000000000
1403638520277829376 -0.000035811 -0.000033249 -0.000058402 -0.000028296 0.000054567 0.000024421 1.000000000
1403638520327829504 -0.000026035 0.000001459 -0.000071547 0.000020327 0.000038343 -0.000036756 1.000000000
1403638520377829376 0.000059818 -0.000008236 0.000038314 0.000009218 -0.000089431 0.000140313 1.000000000
1403638520427829504 -0.000006445 -0.000017846 -0.000074507 -0.000003276 0.000014235 0.000045961 1.000000000
1403638520477829376 0.000056024 -0.000025894 -0.000008458 0.000019227 -0.000098088 0.000151534 1.000000000
1403638520527829504 0.000015148 -0.000008104 -0.000008904 0.000039857 -0.000000389 0.000077187 1.000000000
1403638520577829376 0.000006705 -0.000026116 -0.000059709 0.000020685 -0.000018665 0.000020200 1.000000000
1403638520627829504 0.000008467 0.000009901 -0.000008324 0.000012952 -0.000017952 0.000092966 1.000000000
1403638520677829376 -0.000008021 -0.000077452 -0.000083643 -0.000035007 -0.000031868 0.000104997 1.000000000
1403638520727829504 -0.000028660 -0.000017883 -0.000073691 -0.000001974 0.000007686 0.000051651 1.000000000
1403638520777829376 0.000021160 -0.000009500 0.000020749 0.000013923 0.000000190 0.000089257 1.000000000
1403638520827829504 0.000005794 -0.000031830 0.000009293 0.000000268 0.000011573 0.000128008 1.000000000
1403638520877829376 0.000006129 0.000006389 -0.000022550 0.000039942 0.000018440 -0.000014134 1.000000000
1403638520927829504 0.000003914 -0.000020275 -0.000011013 -0.000029679 0.000021870 0.000053016 1.000000000
1403638520977829376 0.000054935 -0.000011474 0.000061875 -0.000030486 -0.000017240 0.000114787 1.000000000
1403638521027829504 0.000037061 -0.000014738 0.000022573 -0.000016987 -0.000014057 0.000084266 1.000000000
1403638521077829376 0.000045912 -0.000003579 -0.000030067 0.000025797 -0.000109218 0.000180251 1.000000000
1403638521127829504 0.000024114 -0.000013757 -0.000049899 0.000007898 0.000020509 0.000048209 1.000000000
1403638521177829376 0.000002741 0.000004586 0.000008566 0.000033851 -0.000021326 0.000037904 1.000000000
1403638521227829504 0.000070989 0.000001019 -0.000101713 -0.000021680 -0.000011106 0.000000665 1.000000000
1403638521277829376 0.000084755 -0.000014821 -0.000052603 -0.000046407 0.000036727 -0.000017899 1.000000000
1403638521327829504 0.000083994 0.000084862 0.000106705 0.000046798 0.000242293 -0.000592939 0.999999762
1403638521377829376 -0.000041016 0.000055278 0.000045931 0.000044335 0.000136735 -0.000383014 0.999999940
1403638521427829504 -0.000008590 -0.000009719 0.000050479 -0.000039137 0.000021111 0.000015110 1.000000000
1403638521477829376 -0.000023023 -0.000015179 0.000076822 -0.000033091 -0.000010786 -0.000046725 1.000000000
1403638521527829504 -0.000010562 -0.000098898 0.000102506 -0.000056689 0.000050534 0.000675911 0.999999762
1403638521577829376 -0.000299060 -0.000285272 0.000094156 0.000064617 -0.000028412 0.001653191 0.999998629
1403638521627829504 -0.000018901 -0.000137783 0.000095705 -0.000007119 0.000154447 0.000591355 0.999999821
1403638521677829376 0.000089746 0.000013080 0.000143635 -0.000030666 -0.000168174 0.000231783 0.999999940
1403638521727829504 -0.000005841 0.000034127 0.000211066 0.000076577 -0.000185621 0.000349635 0.999999940
1403638521777829376 0.000088566 -0.000053930 0.000182873 0.000069818 -0.000028525 0.000400234 0.999999940
1403638521827829504 0.000040216 -0.000198886 0.000001100 -0.000055933 -0.000190552 0.000252772 0.999999940
1403638521877829376 -0.000104353 -0.000241066 -0.000112429 0.000062767 -0.000130429 0.000189188 0.999999940
1403638521927829504 -0.000482275 -0.000405521 -0.000342425 0.000076321 -0.000767070 0.000712329 0.999999464
1403638521977829376 -0.000656052 -0.000752512 -0.000128105 0.001188972 -0.002089185 -0.000268417 0.999997079
1403638522027829504 -0.001307982 -0.000895468 0.000289813 -0.000085490 -0.003880486 -0.000078401 0.999992490
1403638522077829376 -0.001576566 -0.002108766 0.000076433 -0.002167802 -0.003451718 -0.001585291 0.999990404
1403638522127829504 -0.002278500 -0.005350695 -0.001181690 -0.004877864 -0.004874741 -0.002391668 0.999973357
1403638522177829376 -0.003465250 -0.011895346 -0.003301851 -0.004466398 -0.006980476 -0.001288119 0.999964833
1403638522227829504 -0.004238927 -0.021813009 -0.006504297 -0.001282946 -0.009104861 -0.000325618 0.999957681
1403638522277829376 -0.005077357 -0.034033675 -0.012251341 0.003990613 -0.012488434 0.001516303 0.999912918
1403638522327829504 -0.005749986 -0.050887901 -0.017448435 0.008981684 -0.015772434 0.002406825 0.999832392
1403638522377829376 -0.004430733 -0.068127543 -0.023275953 0.012376138 -0.019003207 0.003152280 0.999737859
1403638522427829504 -0.005069553 -0.089789845 -0.029876916 0.012633267 -0.023291441 0.004776809 0.999637485
1403638522477829376 -0.005320197 -0.110972293 -0.038046006 0.010943579 -0.027554020 0.006322294 0.999540389
1403638522527829504 -0.005172193 -0.133524522 -0.046275057 0.006939858 -0.031688090 0.010510312 0.999418497
1403638522577829376 -0.004809605 -0.155721039 -0.051997129 0.004250759 -0.035884794 0.014450857 0.999242365
1403638522627829504 -0.004411587 -0.178382993 -0.059029516 0.004885260 -0.039423943 0.017003290 0.999065936
1403638522677829376 -0.004486901 -0.201317385 -0.064191073 0.008389645 -0.041690480 0.013569457 0.999003172
1403638522727829504 -0.004725576 -0.224107206 -0.069968417 0.013456256 -0.044578515 0.011058327 0.998854041
1403638522777829376 -0.005045627 -0.249275863 -0.075991131 0.018502794 -0.048463289 0.009657538 0.998606861
1403638522827829504 -0.006522314 -0.273850054 -0.083506174 0.023513049 -0.054028258 0.013055608 0.998177171
1403638522877829376 -0.006063239 -0.299656570 -0.095590018 0.027325191 -0.058569226 0.018155854 0.997744143
1403638522927829504 -0.004849259 -0.324716926 -0.103564650 0.031421486 -0.061798874 0.024301022 0.997297883
1403638522977829376 -0.002152777 -0.349281013 -0.114654623 0.035471827 -0.062978171 0.027282719 0.997011125
1403638523027829504 -0.002703624 -0.365382433 -0.114497088 0.038351856 -0.063455679 0.029125389 0.996822059
1403638523077829376 0.004111748 -0.383279413 -0.129251167 0.039554428 -0.063007772 0.028641459 0.996817470
1403638523127829504 0.005468533 -0.390335351 -0.133990884 0.040876124 -0.063454136 0.028752884 0.996732652
1403638523177829376 0.002018464 -0.396364957 -0.125953719 0.041840319 -0.062355716 0.028505139 0.996769071
1403638523227829504 0.005393677 -0.395134509 -0.125743553 0.043910280 -0.059480477 0.026527798 0.996910334
1403638523277829376 0.010575918 -0.388477236 -0.124123573 0.046731405 -0.054708634 0.023738278 0.997125685
1403638523327829504 0.014857393 -0.375367254 -0.120339766 0.048544809 -0.051638879 0.021934222 0.997244060
1403638523377829376 0.018195812 -0.361414373 -0.115361124 0.048479896 -0.050669994 0.021294212 0.997310758
1403638523427829504 0.021782376 -0.342911988 -0.106490582 0.046854850 -0.049523108 0.019857975 0.997475684
1403638523477829376 0.020846171 -0.314867824 -0.090154588 0.043047577 -0.048122078 0.017050359 0.997767746
1403638523527829504 0.027948825 -0.290467054 -0.087535217 0.035774391 -0.047114857 0.013348415 0.998159409
1403638523577829376 0.034769870 -0.265162468 -0.083654232 0.027156256 -0.045596011 0.009505521 0.998545527
1403638523627829504 0.035645414 -0.241909623 -0.074276872 0.017919546 -0.043255500 0.005891572 0.998885930
1403638523677829376 0.038343333 -0.217671886 -0.069587603 0.010793259 -0.041790713 0.003141382 0.999063134
1403638523727829504 0.039988611 -0.192576081 -0.059371967 0.005894804 -0.040588606 0.000298279 0.999158502
1403638523777829376 0.041935135 -0.169147804 -0.052247129 0.002763339 -0.040407270 -0.001490369 0.999178350
1403638523827829504 0.045100179 -0.147819951 -0.047863405 0.001460122 -0.040376142 -0.003355209 0.999177814
1403638523877829376 0.047561586 -0.126613334 -0.043574601 0.001843540 -0.039288711 -0.005817716 0.999209285
1403638523927829504 0.050366238 -0.107278511 -0.039218560 0.002450451 -0.036877234 -0.010634908 0.999260247
1403638523977829376 0.052162487 -0.091830194 -0.037612308 0.001775353 -0.035042018 -0.015997909 0.999256194
1403638524027829504 0.053070210 -0.080926567 -0.036286321 -0.000440780 -0.033696342 -0.022252418 0.999184251
1403638524077829376 0.053313192 -0.075825863 -0.037625827 -0.003694286 -0.033881418 -0.027106492 0.999051392
1403638524127829504 0.053678498 -0.078415364 -0.040426895 -0.008420826 -0.034731630 -0.030566650 0.998893619
1403638524177829376 0.053559527 -0.088017233 -0.045293581 -0.012570442 -0.036949504 -0.031089360 0.998754323
1403638524227829504 0.053795245 -0.104751848 -0.052339509 -0.014706458 -0.040023781 -0.030324165 0.998630226
1403638524277829376 0.054334816 -0.126293153 -0.060973868 -0.014625291 -0.042481646 -0.028784761 0.998575389
1403638524327829504 0.055084489 -0.151642203 -0.069159746 -0.012761211 -0.046124592 -0.025051398 0.998540044
1403638524377829376 0.055301588 -0.179664642 -0.079090104 -0.009466656 -0.048903942 -0.021487257 0.998527467
1403638524427829504 0.055354811 -0.209610000 -0.088284992 -0.004541617 -0.051570524 -0.018149307 0.998494089
1403638524477829376 0.055491492 -0.239459708 -0.097944506 0.002055667 -0.053171150 -0.016265005 0.998450816
1403638524527829504 0.056338236 -0.271368921 -0.107463278 0.009939719 -0.054762475 -0.014304258 0.998347461
1403638524577829376 0.057447027 -0.300246328 -0.118084580 0.017261263 -0.054779906 -0.013047150 0.998264015
1403638524627829504 0.054567412 -0.327633381 -0.118271515 0.024087407 -0.052615725 -0.011051247 0.998263121
1403638524677829376 0.050831079 -0.347661614 -0.120808497 0.029442294 -0.047912925 -0.010935777 0.998357594
1403638524727829504 0.050335340 -0.374653637 -0.127377883 0.033142634 -0.041628554 -0.012116323 0.998509824
1403638524777829376 0.049117461 -0.391983986 -0.133507922 0.036573082 -0.034025278 -0.013354340 0.998662293
1403638524827829504 0.048161238 -0.407029122 -0.132753491 0.038510155 -0.028420804 -0.014801838 0.998744249
1403638524877829376 0.034706660 -0.379268646 -0.125624180 0.041614279 -0.028461630 -0.013370154 0.998638749
1403638524927829504 0.032799874 -0.419475347 -0.138966888 0.040953580 -0.030901274 -0.012420656 0.998605847
1403638524977829376 0.033227161 -0.404122680 -0.128149897 0.043174077 -0.034921102 -0.011629307 0.998389304
1403638525027829504 0.059350338 -0.385266721 -0.135243803 0.045871619 -0.037619591 -0.013113426 0.998152554
1403638525077829376 0.030911256 -0.384761065 -0.128269732 0.047567379 -0.034960181 -0.016107721 0.998126090
1403638525127829504 0.024385814 -0.369534522 -0.133712590 0.049050447 -0.034628954 -0.018762184 0.998019457
1403638525177829376 0.032221299 -0.354542106 -0.099945366 0.049875326 -0.035486810 -0.020899054 0.997906029
1403638525227829504 0.048411101 -0.355086595 -0.108274683 0.047801491 -0.037359063 -0.023189165 0.997888505
1403638525277829376 0.030013055 -0.335658848 -0.103575520 0.043862928 -0.038277559 -0.024860078 0.997994423
1403638525327829504 0.019292165 -0.311340719 -0.089663543 0.037065063 -0.039447449 -0.026763827 0.998175204
1403638525377829376 0.015278356 -0.283005744 -0.076594949 0.027992848 -0.042387098 -0.027654126 0.998326063
1403638525427829504 0.023092613 -0.264094651 -0.082953542 0.016539479 -0.046355929 -0.026626661 0.998433053
1403638525477829376 0.026055798 -0.245458439 -0.069989838 0.005332995 -0.051306400 -0.024674434 0.998363853
1403638525527829504 0.040803581 -0.225753650 -0.064286239 -0.004921232 -0.055524297 -0.022275880 0.998196661
1403638525577829376 0.038565252 -0.201801836 -0.053594105 -0.011727994 -0.057228651 -0.020708570 0.998077393
1403638525627829504 0.038602449 -0.181982264 -0.046933021 -0.015660547 -0.057348564 -0.019375622 0.998043358
1403638525677829376 0.038733352 -0.164322063 -0.040378638 -0.017267583 -0.056208000 -0.018147878 0.998104811
1403638525727829504 0.039266124 -0.148670241 -0.034515262 -0.016477766 -0.053570565 -0.016720729 0.998288095
1403638525777829376 0.039178248 -0.135255471 -0.029117167 -0.014054117 -0.050473332 -0.014955926 0.998514533
1403638525827829504 0.039036456 -0.124321043 -0.024697047 -0.010771382 -0.046504870 -0.014582069 0.998753548
1403638525877829376 0.039761793 -0.115034893 -0.021309253 -0.007013063 -0.042127583 -0.014960510 0.998975575
1403638525927829504 0.042406797 -0.107578330 -0.018631531 -0.004623461 -0.037512571 -0.016973063 0.999141276
1403638525977829376 0.047799870 -0.102623589 -0.019079424 -0.004193822 -0.034425233 -0.019032756 0.999217212
1403638526027829504 0.056120962 -0.100259177 -0.019732621 -0.004963288 -0.032154270 -0.020169515 0.999267042
1403638526077829376 0.067379005 -0.099885240 -0.021238841 -0.007053468 -0.029493213 -0.019318426 0.999353409
1403638526127829504 0.080848128 -0.101903655 -0.023429658 -0.009435296 -0.026199946 -0.016854877 0.999470055
1403638526177829376 0.096940011 -0.105647422 -0.026936922 -0.011054347 -0.022908987 -0.012942128 0.999592662
1403638526227829504 0.114472352 -0.110540822 -0.031491570 -0.011103964 -0.019120293 -0.009751151 0.999707997
1403638526277829376 0.133559406 -0.116142169 -0.035909459 -0.009458371 -0.014898885 -0.007592607 0.999815464
1403638526327829504 0.153786242 -0.122331165 -0.041335572 -0.006096276 -0.011387744 -0.004453537 0.999906659
1403638526377829376 0.175098062 -0.127431199 -0.046728838 -0.001930272 -0.007828154 -0.001003944 0.999967039
1403638526427829504 0.198602185 -0.132196531 -0.053293988 0.002618457 -0.004087240 0.002447210 0.999985218
1403638526477829376 0.221158013 -0.135895953 -0.059597973 0.007075824 -0.000343227 0.007589853 0.999946117
1403638526527829504 0.246476144 -0.138952479 -0.065925792 0.011562564 0.003462941 0.011811394 0.999857426
1403638526577829376 0.273865908 -0.140830487 -0.071428522 0.016326159 0.007013469 0.016196761 0.999710917
1403638526627829504 0.304772198 -0.142881960 -0.081332795 0.020835230 0.010852022 0.018394530 0.999554753
1403638526677829376 0.334931195 -0.142256036 -0.084126055 0.024888363 0.015170170 0.020412806 0.999366701
1403638526727829504 0.367310822 -0.142346576 -0.092813432 0.027463460 0.019638132 0.021349302 0.999201834
1403638526777829376 0.401191503 -0.141048834 -0.104206197 0.029665217 0.025385804 0.019995093 0.999037385
1403638526827829504 0.434725195 -0.138589248 -0.107187636 0.030808007 0.030572463 0.018472832 0.998886824
1403638526877829376 0.466867715 -0.135756522 -0.113443263 0.030527823 0.033991799 0.018179635 0.998790324
1403638526927829504 0.497693777 -0.132912189 -0.117864653 0.028589539 0.036673293 0.018833097 0.998740733
1403638526977829376 0.527147830 -0.131491169 -0.127878770 0.024698451 0.041221976 0.020307612 0.998638213
1403638527027829504 0.556860566 -0.129389435 -0.129816338 0.019997252 0.047473643 0.023728991 0.998390377
1403638527077829376 0.586449623 -0.128269598 -0.133566946 0.015450324 0.055096798 0.027666334 0.997978032
1403638527127829504 0.613220692 -0.128485680 -0.142213315 0.012026217 0.062533438 0.031565506 0.997471094
1403638527177829376 0.638357043 -0.129618347 -0.148491457 0.010491077 0.070287444 0.035384350 0.996843755
1403638527227829504 0.658852160 -0.132625654 -0.154917657 0.010935045 0.078413799 0.038769037 0.996106744
1403638527277829376 0.677656114 -0.133159667 -0.153597549 0.013296095 0.088118277 0.040394824 0.995201826
1403638527327829504 0.690443695 -0.136151925 -0.154818937 0.016467409 0.097302325 0.040278263 0.994303107
1403638527377829376 0.700163543 -0.139315769 -0.159875169 0.019783167 0.105922461 0.038261421 0.993441045
1403638527427829504 0.705443084 -0.140725374 -0.155517161 0.022592960 0.112584092 0.037188262 0.992688954
1403638527477829376 0.703029692 -0.144008294 -0.154978037 0.024481660 0.117150173 0.036075324 0.992156744
1403638527527829504 0.698337138 -0.146876186 -0.147200882 0.025074931 0.119659111 0.035791647 0.991852760
1403638527577829376 0.697938025 -0.146991476 -0.146139786 0.025367191 0.119697705 0.035819888 0.991839647
1403638527627829504 0.697879434 -0.147404879 -0.145875677 0.025142869 0.117927089 0.035852265 0.992056251
1403638527677829376 0.696597159 -0.147365034 -0.145946398 0.025242364 0.114328578 0.034675740 0.992516696
1403638527727829504 0.694782019 -0.148338214 -0.147068277 0.025188344 0.109764956 0.032675907 0.993100941
1403638527777829376 0.694387078 -0.147827059 -0.145179629 0.024481777 0.103537954 0.032214914 0.993802190
1403638527827829504 0.693889558 -0.148836613 -0.143293917 0.022830054 0.095571488 0.034640156 0.994557679
1403638527877829376 0.680433750 -0.148427218 -0.136784032 0.021355957 0.086975992 0.035754625 0.995339513
1403638527927829504 0.595902264 -0.167413786 -0.140398696 0.019974466 0.083936602 0.037184268 0.995576680
1403638527977829376 0.513919830 -0.170132443 -0.087570101 0.021145750 0.082602665 0.036974639 0.995671868
1403638528027829504 0.463846594 -0.177724287 -0.068919584 0.022617465 0.079894081 0.035061210 0.995929718
1403638528077829376 0.425510436 -0.184315741 -0.055143721 0.024323868 0.075233951 0.033942692 0.996291161
1403638528127829504 0.397850275 -0.187127933 -0.048575811 0.025225148 0.068971127 0.033494554 0.996737063
1403638528177829376 0.368921071 -0.189887390 -0.038418658 0.025075952 0.062712044 0.031966206 0.997204363
1403638528227829504 0.343388230 -0.191948801 -0.030580910 0.024538238 0.055070862 0.031187300 0.997693539
1403638528277829376 0.319388121 -0.194818124 -0.019603143 0.024009721 0.047115177 0.030440606 0.998136818
1403638528327829504 0.297271103 -0.197648406 0.000111960 0.024095783 0.040985133 0.028833879 0.998452902
1403638528377829376 0.279382616 -0.200011879 0.020340450 0.025445381 0.037353646 0.027555732 0.998597980
1403638528427829504 0.264317364 -0.202703148 0.037227616 0.027051505 0.036826316 0.025269659 0.998635828
1403638528477829376 0.250524253 -0.206932411 0.057492826 0.027184056 0.037230041 0.024020800 0.998648047
1403638528527829504 0.239821061 -0.210693255 0.075368851 0.025905538 0.038925070 0.024446761 0.998607099
1403638528577829376 0.230301335 -0.214129150 0.097369023 0.023884559 0.041236240 0.027113359 0.998495817
1403638528627829504 0.222945541 -0.221565083 0.113295406 0.021949498 0.043064956 0.030811600 0.998355746
1403638528677829376 0.219807923 -0.228391945 0.132511094 0.021271657 0.044629727 0.034174312 0.998192251
1403638528727829504 0.209000051 -0.234199271 0.148150876 0.021523606 0.048419580 0.034635466 0.997994304
1403638528777829376 0.215029821 -0.246124581 0.162924618 0.022226386 0.052011263 0.035392649 0.997771621
1403638528827829504 0.215232193 -0.244826615 0.163072124 0.023125382 0.053118289 0.038630355 0.997572720
1403638528877829376 0.205825686 -0.251559526 0.174642548 0.023925036 0.053795103 0.043744750 0.997306406
1403638528927829504 0.208946094 -0.259026140 0.171116740 0.024156194 0.053099152 0.048910089 0.997098148
1403638528977829376 0.207293406 -0.266462564 0.161029369 0.023809984 0.051768195 0.053302620 0.996951342
1403638529027829504 0.208142579 -0.271844238 0.149576217 0.022762192 0.051094864 0.055781748 0.996874928
1403638529077829376 0.201832756 -0.271632373 0.137833476 0.022273781 0.053623434 0.053589243 0.996873379
1403638529127829504 0.191684559 -0.272860855 0.124041811 0.021670412 0.058740981 0.046737127 0.996943057
1403638529177829376 0.181536421 -0.274138123 0.108794808 0.020520911 0.064355746 0.038539305 0.996971369
1403638529227829504 0.172980607 -0.258373082 0.087592870 0.020048520 0.067680091 0.032140944 0.996987700
1403638529277829376 0.163643926 -0.248064205 0.072219431 0.018013429 0.070725679 0.026741652 0.996974587
1403638529327829504 0.153927654 -0.237425134 0.051875990 0.014351935 0.071351975 0.023900315 0.997061551
1403638529377829376 0.144740373 -0.225631654 0.037123129 0.008695853 0.071468845 0.021634486 0.997170269
1403638529427829504 0.132264301 -0.211149290 0.024782360 0.000350298 0.070878290 0.019847730 0.997287393
1403638529477829376 0.121645823 -0.196950302 0.021675281 -0.009487333 0.068846412 0.019610463 0.997389376
1403638529527829504 0.117417730 -0.178048685 0.005595891 -0.019566366 0.066721350 0.020478312 0.997369587
1403638529577829376 0.107486919 -0.163806662 0.010092644 -0.028120378 0.065363102 0.018763129 0.997288764
1403638529627829504 0.101625830 -0.147944257 0.003827967 -0.033534829 0.065399744 0.016877564 0.997152686
1403638529677829376 0.094918370 -0.133569434 0.001272799 -0.035322100 0.065344550 0.015541123 0.997116327
1403638529727829504 0.089666009 -0.120618843 0.000848162 -0.033448212 0.064493746 0.015211500 0.997241437
1403638529777829376 0.084562331 -0.108742580 0.001276457 -0.028419808 0.064742930 0.015321705 0.997379541
1403638529827829504 0.079978287 -0.098397203 0.002206962 -0.021998633 0.064334095 0.016153067 0.997555196
1403638529877829376 0.076161407 -0.088816367 0.004941613 -0.016418453 0.064641714 0.016557561 0.997636080
1403638529927829504 0.073446482 -0.081424698 0.008030994 -0.013012101 0.064578921 0.016586145 0.997689903
1403638529977829376 0.071640506 -0.076084413 0.011905835 -0.011661792 0.064526863 0.016716359 0.997707784
1403638530027829504 0.070529662 -0.072169311 0.017428081 -0.012354556 0.065386713 0.015861008 0.997657418
1403638530077829376 0.070353732 -0.069060221 0.024517972 -0.014075083 0.065510511 0.016640743 0.997613847
1403638530127829504 0.070234992 -0.066811956 0.032673363 -0.016071489 0.067052022 0.017715009 0.997462749
1403638530177829376 0.070890479 -0.065369882 0.040776283 -0.017408878 0.068976194 0.019535741 0.997275054
1403638530227829504 0.071956657 -0.063756660 0.050417542 -0.017641531 0.071838550 0.021624537 0.997025788
1403638530277829376 0.073126473 -0.062208224 0.059435569 -0.017125189 0.074404053 0.023202818 0.996811092
1403638530327829504 0.074919552 -0.060298242 0.067498878 -0.016702209 0.076348260 0.026117180 0.996599197
1403638530377829376 0.077153385 -0.058551371 0.075842977 -0.016732797 0.079426117 0.026332801 0.996352375
1403638530427829504 0.079218000 -0.057174068 0.083603181 -0.016497163 0.081561752 0.026982293 0.996166408
1403638530477829376 0.081120007 -0.056047622 0.089948945 -0.016283261 0.081872739 0.029753936 0.996065497
1403638530527829504 0.083430767 -0.055172373 0.095653147 -0.016108744 0.081650823 0.032102950 0.996013582
1403638530577829376 0.085455276 -0.053911343 0.099905103 -0.016455691 0.083307683 0.032740351 0.995849967
1403638530627829504 0.087640390 -0.052311588 0.103321724 -0.018660976 0.084370419 0.033242386 0.995704949
1403638530677829376 0.089295395 -0.050352313 0.106578663 -0.022313209 0.085371971 0.033820547 0.995524943
1403638530727829504 0.090323105 -0.048311926 0.109035961 -0.026151208 0.085937999 0.034638792 0.995354652
1403638530777829376 0.091409937 -0.046102945 0.111296058 -0.028892124 0.086442374 0.034956206 0.995224118
1403638530827829504 0.092147686 -0.044050023 0.113641039 -0.030244669 0.086427540 0.035294238 0.995173275
1403638530877829376 0.092366487 -0.042526908 0.115278549 -0.030293459 0.085401081 0.034400012 0.995291710
1403638530927829504 0.093154773 -0.041376848 0.116858520 -0.028091567 0.083844811 0.035986803 0.995432496
1403638530977829376 0.093213737 -0.040432096 0.117851429 -0.025865836 0.083508961 0.036563870 0.995500028
1403638531027829504 0.092883408 -0.039309442 0.118650235 -0.023226095 0.082655661 0.036377516 0.995643139
1403638531077829376 0.092777282 -0.038599540 0.118984215 -0.019621117 0.083703332 0.034579221 0.995697260
1403638531127829504 0.092010565 -0.038735516 0.118622281 -0.016283514 0.083414838 0.035325475 0.995755434
1403638531177829376 0.091166690 -0.038981445 0.118707724 -0.014936365 0.082264356 0.034308754 0.995907843
1403638531227829504 0.090764761 -0.038116496 0.119646393 -0.015832629 0.083550647 0.031177508 0.995889843
1403638531277829376 0.089988038 -0.037332647 0.120455615 -0.012668611 0.084881276 0.029273642 0.995880365
1403638531327829504 0.089317001 -0.037446652 0.120720640 -0.009095662 0.084741794 0.030598624 0.995891452
1403638531377829376 0.088896975 -0.037106514 0.120887645 -0.010414996 0.084756777 0.030052474 0.995893896
1403638531427829504 0.089446269 -0.036931530 0.120887309 -0.009896003 0.084794052 0.029544802 0.995911181
1403638531477829376 0.089500330 -0.037147000 0.120538719 -0.008199884 0.085049435 0.029940035 0.995893061
1403638531527829504 0.089495696 -0.036983307 0.120540760 -0.008747516 0.084918849 0.029775664 0.995904446
1403638531577829376 0.089563407 -0.036781207 0.120664887 -0.009146531 0.085371412 0.028229227 0.995907187
1403638531627829504 0.089486137 -0.036678653 0.120198824 -0.009028388 0.085009277 0.028172735 0.995940804
1403638531677829376 0.089300096 -0.036792725 0.120017417 -0.009208270 0.084144525 0.030342840 0.995948911
1403638531727829504 0.089334264 -0.036736920 0.120130807 -0.009377792 0.084680870 0.028881356 0.995945334
1403638531777829376 0.089508027 -0.036821652 0.120435029 -0.009054662 0.084122397 0.030024303 0.995961845
1403638531827829504 0.089325428 -0.036788695 0.120085053 -0.009413400 0.084599443 0.029336294 0.995938599
1403638531877829376 0.089375734 -0.036774166 0.120258719 -0.009186307 0.084287561 0.029714432 0.995955944
1403638531927829504 0.089271396 -0.036906730 0.120090812 -0.009407636 0.084340490 0.029544886 0.995954454
1403638531977829376 0.089463629 -0.036791921 0.120255597 -0.009300059 0.084477730 0.029451881 0.995946586
1403638532027829504 0.089238867 -0.036806986 0.120474368 -0.009235762 0.084441721 0.030037612 0.995932758
1403638532077829376 0.089366525 -0.036747757 0.120242342 -0.009388132 0.084643863 0.028827794 0.995949924
1403638532127829504 0.089284688 -0.036787253 0.120048173 -0.009070790 0.084272683 0.030079730 0.995947301
1403638532177829376 0.089318573 -0.036708146 0.119824640 -0.009194029 0.084614918 0.029158337 0.995944560
1403638532227829504 0.089277945 -0.036749251 0.120195761 -0.009163722 0.084328905 0.029581284 0.995956600
1403638532277829376 0.089317739 -0.036754705 0.120183960 -0.009121457 0.084503651 0.029686967 0.995939076
1403638532327829504 0.089325964 -0.036750212 0.120569780 -0.009281636 0.084568121 0.029680535 0.995932281
1403638532377829376 0.089219511 -0.036778681 0.120167203 -0.009330833 0.084396131 0.029544877 0.995950460
1403638532427829504 0.089256063 -0.036729444 0.120466605 -0.009278081 0.084617734 0.029261358 0.995940566
1403638532477829376 0.089210212 -0.036875907 0.120339781 -0.009209247 0.084460601 0.029925412 0.995934784
1403638532527829504 0.089342102 -0.036718823 0.120283850 -0.009299926 0.084479026 0.029128032 0.995956004
1403638532577829376 0.089232147 -0.036872454 0.120154664 -0.009379054 0.084411636 0.029818900 0.995940506
1403638532627829504 0.089378476 -0.036744371 0.120433435 -0.009352289 0.084397979 0.029461548 0.995952547
1403638532677829376 0.089241542 -0.036911670 0.120091937 -0.009377753 0.084459528 0.029907621 0.995933831
1403638532727829504 0.089255437 -0.037010264 0.120015360 -0.009354888 0.084474914 0.029695505 0.995939076
1403638532777829376 0.089184560 -0.037094075 0.119756691 -0.009503033 0.084544539 0.029439921 0.995939374
1403638532827829504 0.089242898 -0.037023559 0.119952418 -0.009326543 0.084461361 0.029718252 0.995939791
1403638532877829376 0.089314140 -0.036766466 0.120427132 -0.009304630 0.084477052 0.029542278 0.995943904
1403638532927829504 0.089332834 -0.036798004 0.120398358 -0.009328526 0.084416866 0.029787766 0.995941520
1403638532977829376 0.089249723 -0.036863048 0.120198026 -0.009360870 0.084574424 0.029598482 0.995933473
1403638533027829504 0.089282185 -0.036727585 0.120127015 -0.009133550 0.084402308 0.029639633 0.995948970
1403638533077829376 0.089235567 -0.036819935 0.120031439 -0.009385557 0.084417865 0.029662270 0.995944619
1403638533127829504 0.089305796 -0.036840577 0.120068692 -0.009324235 0.084421359 0.029508177 0.995949507
1403638533177829376 0.089441121 -0.036791954 0.120117128 -0.009225138 0.084259830 0.029701998 0.995958328
1403638533227829504 0.089377478 -0.036770821 0.120070435 -0.009202613 0.084375598 0.029511616 0.995954394
1403638533277829376 0.089258909 -0.036848184 0.119923994 -0.009313039 0.084522292 0.029454291 0.995942593
1403638533327829504 0.089330189 -0.036856502 0.120090030 -0.009318347 0.084519185 0.029591678 0.995938778
1403638533377829376 0.089398474 -0.036794346 0.120050773 -0.009349940 0.084481195 0.029467084 0.995945394
1403638533427829504 0.089331754 -0.036832429 0.120037228 -0.009326587 0.084405676 0.029604476 0.995947957
1403638533477829376 0.089410685 -0.036784329 0.120342486 -0.009284161 0.084550038 0.029402882 0.995942056
1403638533527829504 0.089343354 -0.036860060 0.120127358 -0.009315656 0.084452629 0.029574523 0.995944917
1403638533577829376 0.089225046 -0.036874671 0.120052099 -0.009480710 0.084449880 0.029420318 0.995948195
1403638533627829504 0.089234062 -0.036872812 0.120290324 -0.009307350 0.084578551 0.029427378 0.995938659
1403638533677829376 0.089266546 -0.036864072 0.120141871 -0.009263007 0.084446020 0.029606903 0.995945036
1403638533727829504 0.089302093 -0.036856189 0.120188065 -0.009384467 0.084530115 0.029428674 0.995942056
1403638533777829376 0.089170583 -0.036871471 0.120217316 -0.009342352 0.084569916 0.029684585 0.995931447
1403638533827829504 0.089271665 -0.036836408 0.120183498 -0.009262033 0.084520169 0.029365292 0.995945871
1403638533877829376 0.089219950 -0.036863450 0.120082065 -0.009378452 0.084296539 0.029631849 0.995955884
1403638533927829504 0.089394569 -0.036821757 0.120248288 -0.009251266 0.084294386 0.029519938 0.995960593
1403638533977829376 0.089320652 -0.036864161 0.120133638 -0.009292775 0.084363192 0.029732795 0.995948017
1403638534027829504 0.089287966 -0.036801375 0.120232344 -0.009309411 0.084644660 0.029544348 0.995929599
1403638534077829376 0.089513682 -0.036724269 0.120229959 -0.009092718 0.084804557 0.029868325 0.995908320
1403638534127829504 0.089256696 -0.036839746 0.120026745 -0.009339970 0.084752299 0.029942473 0.995908260
1403638534177829376 0.089263454 -0.036907271 0.120172389 -0.009320348 0.084745631 0.029972184 0.995908082
1403638534227829504 0.089171782 -0.036915615 0.119997799 -0.009373911 0.084743336 0.029982312 0.995907485
1403638534277829376 0.089323312 -0.036925025 0.120110288 -0.009376653 0.084218308 0.030216774 0.995944917
1403638534327829504 0.089395158 -0.036851756 0.120421775 -0.009224997 0.084311157 0.030094106 0.995942175
1403638534377829376 0.089231573 -0.036920104 0.120096534 -0.009357124 0.084401794 0.030080058 0.995933712
1403638534427829504 0.089329734 -0.036868140 0.120127007 -0.009309182 0.084303521 0.030270012 0.995936692
1403638534477829376 0.089323819 -0.036921155 0.120362833 -0.009218407 0.084791355 0.030156940 0.995899558
1403638534527829504 0.089530542 -0.036814973 0.120289668 -0.009111627 0.084513701 0.030353881 0.995918214
1403638534577829376 0.089292966 -0.036868911 0.120147914 -0.009351823 0.084276639 0.029959878 0.995948017
1403638534627829504 0.089280225 -0.036931597 0.120107122 -0.009340399 0.084355056 0.030080006 0.995937824
1403638534677829376 0.089340024 -0.036878102 0.120373107 -0.009248669 0.084007129 0.030017596 0.995970011
1403638534727829504 0.089378402 -0.036847997 0.120174929 -0.009188141 0.084070243 0.030078465 0.995963395
1403638534777829376 0.089406379 -0.036837980 0.120277502 -0.009239839 0.084130481 0.029855411 0.995964527
1403638534827829504 0.089306384 -0.036881015 0.120183319 -0.009326245 0.084265150 0.029645920 0.995958567
1403638534877829376 0.089335941 -0.036862627 0.120238774 -0.009325265 0.084546633 0.029676104 0.995933831
1403638534927829504 0.089263789 -0.036851298 0.120307803 -0.009374229 0.084719926 0.029488740 0.995924234
1403638534977829376 0.089409404 -0.036859818 0.120288409 -0.009393252 0.084716819 0.029671835 0.995918870
1403638535027829504 0.089301750 -0.036814086 0.120267704 -0.009352709 0.084665008 0.029494699 0.995928943
1403638535077829376 0.089297265 -0.036797803 0.120100126 -0.009288210 0.084611043 0.029709678 0.995927691
1403638535127829504 0.089377545 -0.036775444 0.120260686 -0.009224156 0.084560454 0.029403256 0.995941699
1403638535177829376 0.089280181 -0.036849208 0.120194919 -0.009298231 0.084612608 0.029973190 0.995919585
1403638535227829504 0.089343637 -0.036806464 0.120210342 -0.009263407 0.084528454 0.029591301 0.995938480
1403638535277829376 0.089271419 -0.036857363 0.120049968 -0.009302946 0.084472001 0.029935429 0.995932639
1403638535327829504 0.089236274 -0.036813833 0.120163515 -0.009231099 0.084649898 0.029626211 0.995927453
1403638535377829376 0.089255549 -0.036830138 0.120133832 -0.009349934 0.084542409 0.029712811 0.995932877
1403638535427829504 0.089316688 -0.036807392 0.120221168 -0.009255574 0.084477320 0.029678641 0.995940268
1403638535477829376 0.089285947 -0.036783531 0.120289177 -0.009283842 0.084552735 0.029808650 0.995929718
1403638535527829504 0.089255109 -0.036810793 0.120264813 -0.009258208 0.084521621 0.029736949 0.995934784
1403638535577829376 0.089287281 -0.036800932 0.120126098 -0.009209054 0.084359013 0.029949663 0.995942652
1403638535627829504 0.089295626 -0.036896836 0.120087653 -0.009397372 0.084482774 0.029818406 0.995934308
1403638535677829376 0.089245237 -0.036931071 0.120079823 -0.009376057 0.084513329 0.029775919 0.995933235
1403638535727829504 0.089238375 -0.036864296 0.120076790 -0.009373558 0.084558785 0.029759109 0.995929897
1403638535777829376 0.089217275 -0.036850967 0.120210037 -0.009353790 0.084657416 0.029666498 0.995924473
1403638535827829504 0.089316063 -0.036870129 0.120200947 -0.009341735 0.084522493 0.029910201 0.995928705
1403638535877829376 0.089328766 -0.036831129 0.120212704 -0.009310734 0.084413849 0.029847885 0.995940089
1403638535927829504 0.089252546 -0.036859278 0.120078884 -0.009383776 0.084454887 0.029826127 0.995936573
1403638535977829376 0.089368835 -0.036797170 0.120086901 -0.009318724 0.084291898 0.029893501 0.995948970
1403638536027829504 0.089270025 -0.036805984 0.120042615 -0.009423932 0.084432155 0.029728763 0.995941043
1403638536077829376 0.089314640 -0.036807410 0.120025769 -0.009298065 0.084326804 0.029665893 0.995953023
1403638536127829504 0.089333035 -0.036786411 0.120134585 -0.009330010 0.084356114 0.029690668 0.995949507
1403638536177829376 0.089345157 -0.036797658 0.120130658 -0.009318734 0.084312983 0.029670607 0.995953918
1403638536227829504 0.089264154 -0.036867540 0.120103009 -0.009351171 0.084409855 0.029810501 0.995941162
1403638536277829376 0.089279801 -0.036814094 0.120004997 -0.009283641 0.084377728 0.029787049 0.995945215
1403638536327829504 0.089272916 -0.036868908 0.120159104 -0.009381601 0.084391557 0.029831786 0.995941818
1403638536377829376 0.089337960 -0.036828112 0.120249376 -0.009294169 0.084520057 0.029714881 0.995935202
1403638536427829504 0.089242809 -0.036875740 0.120020896 -0.009331982 0.084431060 0.029824259 0.995939136
1403638536477829376 0.089308493 -0.036854945 0.120123781 -0.009386370 0.084493101 0.029776113 0.995934844
1403638536527829504 0.089390025 -0.036803313 0.120187305 -0.009289105 0.084251486 0.029959070 0.995950758
1403638536577829376 0.089340791 -0.036804561 0.120038293 -0.009319925 0.084316686 0.029780425 0.995950341
1403638536627829504 0.089261219 -0.036849968 0.119966537 -0.009296248 0.084358744 0.029873220 0.995944202
1403638536677829376 0.089295946 -0.036870420 0.119891472 -0.009333171 0.084353268 0.029742688 0.995948195
1403638536727829504 0.089278139 -0.036818318 0.120022014 -0.009352141 0.084333822 0.029584827 0.995954394
1403638536777829376 0.089277767 -0.036794785 0.119958058 -0.009280282 0.084370553 0.029736504 0.995947421
1403638536827829504 0.089334473 -0.036850728 0.120120749 -0.009362386 0.084405147 0.029694611 0.995944977
1403638536877829376 0.089288086 -0.036796294 0.120093264 -0.009296487 0.084407590 0.029835351 0.995941162
1403638536927829504 0.089400381 -0.036818128 0.120115004 -0.009311249 0.084258795 0.029639225 0.995959520
1403638536977829376 0.089277193 -0.036901221 0.119967483 -0.009340492 0.084370390 0.030009724 0.995938659
1403638537027829504 0.089253761 -0.036831841 0.120048866 -0.009258570 0.084403537 0.029668959 0.995946825
1403638537077829376 0.089337796 -0.036834776 0.120128997 -0.009238844 0.084265217 0.030077647 0.995946467
1403638537127829504 0.089417793 -0.036792047 0.120283566 -0.009242035 0.084359616 0.029712293 0.995949388
1403638537177829376 0.089332305 -0.036916632 0.120055690 -0.009267979 0.084344894 0.029896406 0.995944917
1403638537227829504 0.089339897 -0.036840346 0.120022610 -0.009206289 0.084382981 0.030064838 0.995937169
1403638537277829376 0.089374579 -0.036857951 0.120147064 -0.009188459 0.084391490 0.029893257 0.995941818
1403638537327829504 0.089399233 -0.036786515 0.120195612 -0.009182959 0.084415875 0.029861497 0.995940745
1403638537377829376 0.089333206 -0.036788750 0.120095976 -0.009250207 0.084513634 0.029603064 0.995939553
1403638537427829504 0.089330666 -0.036787629 0.120070830 -0.009174837 0.084433749 0.029909486 0.995937824
1403638537477829376 0.089383215 -0.036820650 0.120158061 -0.009228996 0.084425382 0.029945446 0.995936990
1403638537527829504 0.089342706 -0.036789350 0.120114513 -0.009133837 0.084277928 0.029990004 0.995948970
1403638537577829376 0.089333363 -0.036762767 0.120099716 -0.009147952 0.084431171 0.029747557 0.995943189
1403638537627829504 0.089435339 -0.036795780 0.120235369 -0.009074090 0.084213570 0.030169657 0.995949566
1403638537677829376 0.089344814 -0.036898762 0.120082118 -0.009284950 0.084457844 0.029712476 0.995940685
1403638537727829504 0.089336641 -0.036808506 0.120056264 -0.009118211 0.084515311 0.029659687 0.995938897
1403638537777829376 0.089376904 -0.036845047 0.120134547 -0.009169987 0.084329627 0.029778251 0.995950639
1403638537827829504 0.089336008 -0.036839534 0.120046087 -0.009168773 0.084448546 0.030021243 0.995933294
1403638537877829376 0.089371800 -0.036799561 0.120026514 -0.009070437 0.084494352 0.029695554 0.995940030
1403638537927829504 0.089446150 -0.036787838 0.120225646 -0.009030861 0.084383816 0.029651504 0.995951056
1403638537977829376 0.089324221 -0.036831815 0.120030113 -0.009060451 0.084597073 0.029746497 0.995929897
1403638538027829504 0.089389473 -0.036792859 0.120095715 -0.009058435 0.084557407 0.029587045 0.995938063
1403638538077829376 0.089355998 -0.036906078 0.120155931 -0.009206520 0.084620491 0.029832954 0.995923996
1403638538127829504 0.089476556 -0.036855161 0.120183639 -0.009046525 0.084533542 0.029620202 0.995939195
1403638538177829376 0.089453742 -0.036806963 0.120228097 -0.009003607 0.084643610 0.029730102 0.995926976
1403638538227829504 0.089463063 -0.036868539 0.120263211 -0.009063683 0.084539130 0.029912833 0.995929837
1403638538277829376 0.089372568 -0.036868315 0.120367624 -0.008917419 0.084563345 0.029794129 0.995932639
1403638538327829504 0.089457452 -0.036851421 0.120301165 -0.009122887 0.084531315 0.029876377 0.995931029
1403638538377829376 0.089562029 -0.036852576 0.120370150 -0.008925680 0.084583335 0.029740557 0.995932460
1403638538427829504 0.089363508 -0.036916688 0.120468311 -0.008660483 0.084642209 0.029639794 0.995932758
1403638538477829376 0.089520507 -0.036922030 0.120239541 -0.008843151 0.084568053 0.029785933 0.995933175
1403638538527829504 0.089461543 -0.037023891 0.120137937 -0.008577268 0.084472150 0.030073252 0.995934963
1403638538577829376 0.089434065 -0.036910586 0.120345019 -0.008808460 0.084642366 0.029409444 0.995938301
1403638538627829504 0.089483142 -0.037129108 0.120153233 -0.008350735 0.084504008 0.030310573 0.995926976
1403638538677829376 0.089404777 -0.037130330 0.120168880 -0.008567849 0.084614493 0.029994287 0.995925367
1403638538727829504 0.089491986 -0.037245251 0.119995445 -0.007831790 0.084588915 0.030031729 0.995932460
1403638538777829376 0.089634173 -0.037426654 0.120224983 -0.006689974 0.083993405 0.030476160 0.995977700
1403638538827829504 0.089327924 -0.037763078 0.120753750 -0.006619785 0.083708704 0.030416140 0.996003985
1403638538877829376 0.089068197 -0.038537361 0.121883541 -0.005330713 0.083183683 0.030264201 0.996060312
1403638538927829504 0.089137554 -0.040283795 0.122714847 -0.001970186 0.083692402 0.028908199 0.996070266
1403638538977829376 0.089275733 -0.042392757 0.124394968 0.002884496 0.083594128 0.028767448 0.996080399
1403638539027829504 0.089546621 -0.044529062 0.126128316 0.006443572 0.084715381 0.029060325 0.995960474
1403638539077829376 0.089820787 -0.047717866 0.129322588 0.012421335 0.085803524 0.029416818 0.995800197
1403638539127829504 0.089764737 -0.051775694 0.132270470 0.017986709 0.085773326 0.029874843 0.995704234
1403638539177829376 0.090426527 -0.057188649 0.134680778 0.022037098 0.085677825 0.029989948 0.995627582
1403638539227829504 0.090657368 -0.065224126 0.136700064 0.026646769 0.085461937 0.029269312 0.995554864
1403638539277829376 0.095289402 -0.076345451 0.131010056 0.028130937 0.084911838 0.029350940 0.995558739
1403638539327829504 0.095678091 -0.088001393 0.131126434 0.027863190 0.084442712 0.029547455 0.995600343
1403638539377829376 0.096199691 -0.101178274 0.130782872 0.026608799 0.084248655 0.029233338 0.995660365
1403638539427829504 0.092340842 -0.114824615 0.135701269 0.025603591 0.084109336 0.028925883 0.995707452
1403638539477829376 0.093254216 -0.130965725 0.135307699 0.023333699 0.083670102 0.028373316 0.995816171
1403638539527829504 0.094250016 -0.148578405 0.132283628 0.022429202 0.083047591 0.027917694 0.995901883
1403638539577829376 0.097934172 -0.165093586 0.124250069 0.021982744 0.082549989 0.027643563 0.995960891
1403638539627829504 0.098801382 -0.181936592 0.124189436 0.021412374 0.081690356 0.027819686 0.996039271
1403638539677829376 0.100173935 -0.196833491 0.125409499 0.021159813 0.080855466 0.028565234 0.996091723
1403638539727829504 0.101268344 -0.207451567 0.125214770 0.020522304 0.080506481 0.027441675 0.996164858
1403638539777829376 0.100776665 -0.216910571 0.129053697 0.019164646 0.080166057 0.026526812 0.996244192
1403638539827829504 0.100268669 -0.224278346 0.132061079 0.017701527 0.079657860 0.026848391 0.996303380
1403638539877829376 0.106436886 -0.230510369 0.143759504 0.014697063 0.078749262 0.026904648 0.996422946
1403638539927829504 0.104377598 -0.237816527 0.143529937 0.010996087 0.077906474 0.027017603 0.996533871
1403638539977829376 0.099597976 -0.243059203 0.158962473 0.006628232 0.077572890 0.027584631 0.996582985
1403638540027829504 0.100312494 -0.249660522 0.166016832 0.001415070 0.077206202 0.028068250 0.996618986
1403638540077829376 0.100481674 -0.258331001 0.171472639 -0.004012352 0.077062659 0.027622713 0.996635497
1403638540127829504 0.100855552 -0.267117232 0.178488582 -0.009403503 0.076745681 0.027976872 0.996613741
1403638540177829376 0.109127522 -0.274047077 0.180700436 -0.011418126 0.076025836 0.027780458 0.996653378
1403638540227829504 0.110428333 -0.290381461 0.199963570 -0.009614370 0.075982325 0.026937321 0.996698856
1403638540277829376 0.112319678 -0.304067671 0.210738674 -0.004411502 0.075935349 0.025715359 0.996771336
1403638540327829504 0.116213769 -0.308835298 0.221431568 0.001913258 0.075952314 0.025651505 0.996779621
1403638540377829376 0.121508390 -0.317058057 0.239063874 0.007336427 0.074972175 0.024045192 0.996868670
1403638540427829504 0.111161307 -0.335196912 0.262843102 0.010157696 0.073925905 0.022247829 0.996963799
1403638540477829376 0.114021450 -0.346123695 0.280366778 0.011661479 0.070046023 0.020575188 0.997263372
1403638540527829504 0.108987585 -0.350347340 0.304129839 0.012246045 0.064841494 0.017586010 0.997665465
1403638540577829376 0.104111977 -0.354153782 0.326142192 0.013122694 0.058240462 0.014599159 0.998109579
1403638540627829504 0.116730094 -0.377262741 0.340649486 0.012753025 0.049307201 0.011775477 0.998632789
1403638540677829376 0.117393382 -0.393231481 0.356602907 0.012920308 0.040922463 0.005678621 0.999062657
1403638540727829504 0.120267421 -0.398173869 0.378910035 0.015266308 0.031269219 -0.001937836 0.999392509
1403638540777829376 0.114514023 -0.410470873 0.392750353 0.015252254 0.021085789 -0.009705336 0.999614179
1403638540827829504 0.111590862 -0.417149901 0.423401773 0.016569445 0.009691630 -0.018908441 0.999636948
1403638540877829376 0.107545003 -0.431711257 0.446999431 0.016216507 -0.002990272 -0.027514776 0.999485373
1403638540927829504 0.101118028 -0.447148472 0.451126486 0.016604291 -0.015555282 -0.035813387 0.999099433
1403638540977829376 0.097495571 -0.464667976 0.471997172 0.016563935 -0.028994415 -0.041621860 0.998575270
1403638541027829504 0.084766075 -0.462524623 0.511174619 0.018091744 -0.040347166 -0.046696309 0.997929990
1403638541077829376 0.066229753 -0.483712643 0.531830370 0.018446514 -0.050112911 -0.049909860 0.997325122
1403638541127829504 0.060166128 -0.490773052 0.550262749 0.019455245 -0.059009552 -0.053034615 0.996657789
1403638541177829376 0.049412519 -0.501657426 0.579727709 0.019476436 -0.065824278 -0.055597592 0.996090710
1403638541227829504 0.036634602 -0.500646412 0.616102278 0.019726723 -0.071275838 -0.057772983 0.995586693
1403638541277829376 0.029685669 -0.510823071 0.634708524 0.020082938 -0.075211182 -0.059861884 0.995166540
1403638541327829504 0.007538617 -0.525805056 0.656508029 0.019346099 -0.077579245 -0.060535859 0.994958580
1403638541377829376 -0.002493396 -0.535063863 0.686549902 0.019434761 -0.079501532 -0.060673226 0.994796753
1403638541427829504 -0.021359913 -0.553231180 0.707803488 0.018717265 -0.080425486 -0.060310680 0.994758248
1403638541477829376 -0.033732884 -0.567660570 0.722407341 0.019549655 -0.080886737 -0.060566016 0.994689345
1403638541527829504 -0.052374430 -0.586457849 0.749782205 0.020560488 -0.080074459 -0.061458532 0.994679928
1403638541577829376 -0.062258556 -0.607010484 0.764642894 0.021574862 -0.081223734 -0.061413955 0.994567990
1403638541627829504 -0.083421931 -0.627020121 0.789779067 0.022773437 -0.082808457 -0.062729552 0.994328439
1403638541677829376 -0.118549965 -0.644746482 0.806274235 0.023969481 -0.085528255 -0.061780676 0.994129539
1403638541727829504 -0.145588189 -0.673694372 0.827005029 0.024511853 -0.090177357 -0.062450875 0.993663490
1403638541777829376 -0.167951420 -0.695051551 0.844108820 0.024571838 -0.097017638 -0.061104678 0.993101239
1403638541827829504 -0.194358736 -0.724736094 0.864459515 0.024311274 -0.104338706 -0.060904387 0.992377460
1403638541877829376 -0.214380503 -0.747788429 0.884797275 0.024602056 -0.112395465 -0.061471485 0.991455138
1403638541927829504 -0.243831515 -0.767311096 0.897474945 0.023767438 -0.120975100 -0.063670032 0.990326345
1403638541977829376 -0.275027871 -0.788005829 0.912338257 0.023044817 -0.129834354 -0.066779926 0.989015877
1403638542027829504 -0.295177400 -0.811035395 0.926256299 0.022102766 -0.140759349 -0.069473565 0.987355888
1403638542077829376 -0.330818594 -0.824082494 0.939627707 0.021762479 -0.150968894 -0.073521554 0.985560417
1403638542127829504 -0.365383118 -0.852650225 0.970593750 0.021244755 -0.162136316 -0.077080667 0.983523786
1403638542177829376 -0.401616096 -0.887975812 0.978436708 0.020037433 -0.174349681 -0.081029773 0.981139600
1403638542227829504 -0.439425588 -0.897548854 0.999048769 0.019282388 -0.186494634 -0.085749224 0.978516698
1403638542277829376 -0.461184025 -0.902995169 1.013195395 0.018909387 -0.199533090 -0.091950938 0.975383997
1403638542327829504 -0.493143201 -0.912166774 1.050265908 0.019594392 -0.212323099 -0.097423129 0.972133577
1403638542377829376 -0.519269049 -0.926787555 1.047537684 0.023259901 -0.222839758 -0.102495141 0.969172955
1403638542427829504 -0.550250411 -0.946526110 1.064342976 0.029395519 -0.231640175 -0.109034225 0.966224730
1403638542477829376 -0.576212347 -0.947591543 1.093232274 0.038959902 -0.239365757 -0.115814112 0.963209867
1403638542527829504 -0.610763252 -0.960080862 1.109363079 0.046313461 -0.243413061 -0.124225907 0.960818946
1403638542577829376 -0.652603149 -0.972010314 1.143157005 0.052935660 -0.246272907 -0.132440969 0.958648443
1403638542627829504 -0.677848399 -0.975948036 1.157411218 0.055682246 -0.249422893 -0.137905553 0.956906319
1403638542677829376 -0.709878623 -0.997124434 1.157010198 0.055363704 -0.252130657 -0.141070962 0.955753088
1403638542727829504 -0.748119533 -1.014214754 1.170718551 0.051511139 -0.255188942 -0.139677182 0.955361426
1403638542777829376 -0.772613764 -1.014930129 1.190851927 0.047799751 -0.260116547 -0.134672299 0.954943955
1403638542827829504 -0.807869136 -1.027400374 1.205141544 0.044142354 -0.262986988 -0.131521165 0.954773009
1403638542877829376 -0.837332368 -1.052771211 1.203214288 0.038188022 -0.265141129 -0.128546670 0.954839051
1403638542927829504 -0.893461823 -1.059068680 1.200183630 0.034655467 -0.265520126 -0.125347614 0.955293655
1403638542977829376 -0.929866612 -1.081259251 1.202194929 0.030872304 -0.266517937 -0.123190090 0.955426276
1403638543027829504 -0.952415466 -1.100747943 1.221155167 0.027724987 -0.268411219 -0.120803475 0.955297470
1403638543077829376 -1.009772182 -1.112509489 1.209283710 0.026081003 -0.267352223 -0.119100451 0.955854416
1403638543127829504 -1.038570523 -1.124474764 1.216585636 0.025486389 -0.267776281 -0.117465064 0.955954075
1403638543177829376 -1.088390350 -1.137196541 1.219853044 0.025387786 -0.266778260 -0.116889894 0.956306219
1403638543227829504 -1.131177664 -1.157225847 1.218409061 0.024609633 -0.265872627 -0.116174378 0.956665874
1403638543277829376 -1.171189785 -1.171412110 1.224178791 0.025106639 -0.265691012 -0.114754237 0.956874788
1403638543327829504 -1.213939548 -1.179563761 1.228538990 0.024413614 -0.264906704 -0.114194907 0.957177103
1403638543377829376 -1.252773523 -1.187009335 1.237332940 0.024093376 -0.265076518 -0.114243008 0.957132459
1403638543427829504 -1.290512800 -1.195363641 1.242610335 0.024008023 -0.267183542 -0.114949360 0.956463933
1403638543477829376 -1.327949286 -1.200832486 1.251195550 0.023824416 -0.270147324 -0.116679102 0.955425978
1403638543527829504 -1.372736454 -1.204960704 1.255349636 0.023330994 -0.274783224 -0.118736930 0.953861296
1403638543577829376 -1.410158396 -1.215399384 1.261128426 0.022855014 -0.280960619 -0.122722149 0.951566100
1403638543627829504 -1.446254253 -1.218060136 1.268811464 0.022974113 -0.288154304 -0.128691643 0.948618889
1403638543677829376 -1.492983818 -1.217982888 1.284620762 0.024161490 -0.297527224 -0.133660823 0.945001900
1403638543727829504 -1.524965525 -1.215987802 1.295654893 0.024798313 -0.307751089 -0.139258116 0.940893948
1403638543777829376 -1.572344542 -1.230065703 1.291372180 0.025527131 -0.318092674 -0.145315588 0.936508834
1403638543827829504 -1.614356518 -1.236814976 1.294348240 0.027503720 -0.328375608 -0.152391523 0.931767046
1403638543877829376 -1.663614750 -1.249511242 1.291108847 0.028410060 -0.339713097 -0.157949358 0.926736176
1403638543927829504 -1.730157852 -1.258546472 1.296500087 0.029444899 -0.351222605 -0.162453651 0.921620607
1403638543977829376 -1.784387946 -1.263484478 1.301019907 0.030256966 -0.361568332 -0.165426567 0.917053401
1403638544027829504 -1.833729982 -1.273448110 1.296859026 0.028779341 -0.370967895 -0.166929185 0.913065851
1403638544077829376 -1.881852388 -1.277630568 1.290476322 0.026754260 -0.379459500 -0.166545451 0.909701765
1403638544127829504 -1.925668478 -1.300801516 1.288630366 0.025291080 -0.386023253 -0.167190373 0.906859279
1403638544177829376 -1.971630454 -1.322112203 1.301791310 0.023694664 -0.392995685 -0.165722460 0.904173076
1403638544227829504 -2.027064562 -1.332885146 1.299458385 0.024171086 -0.396657199 -0.165380701 0.902622879
1403638544277829376 -2.071712017 -1.348053217 1.309011459 0.023647608 -0.400482506 -0.164888784 0.901036203
1403638544327829504 -2.128485441 -1.367331624 1.283407688 0.022610463 -0.400685161 -0.166015849 0.900765777
1403638544377829376 -2.176547766 -1.377543449 1.290949464 0.021421362 -0.401926965 -0.165761963 0.900288165
1403638544427829504 -2.228880882 -1.382094145 1.295127749 0.020654507 -0.402211010 -0.166467965 0.900048971
1403638544477829376 -2.273154020 -1.389032006 1.301521420 0.020653239 -0.401777416 -0.167780846 0.899998844
1403638544527829504 -2.318988800 -1.393383145 1.307910204 0.022426125 -0.401544690 -0.167108268 0.900185406
1403638544577829376 -2.372843266 -1.402622223 1.314101934 0.025343467 -0.402647734 -0.166088402 0.899803996
1403638544627829504 -2.422711849 -1.409857988 1.322923660 0.030670036 -0.404792964 -0.164165333 0.899028242
1403638544677829376 -2.475333929 -1.427494049 1.328279138 0.034683496 -0.406335562 -0.162667021 0.898458660
1403638544727829504 -2.523878336 -1.441254377 1.334683061 0.036430322 -0.407465726 -0.162571415 0.897894800
1403638544777829376 -2.570376635 -1.458053350 1.342509151 0.034760948 -0.407975674 -0.163078219 0.897637486
1403638544827829504 -2.613280296 -1.458858013 1.354701281 0.033304915 -0.408211082 -0.164786413 0.897273660
1403638544877829376 -2.662849903 -1.471153498 1.356741548 0.029298857 -0.407823682 -0.166030630 0.897360206
1403638544927829504 -2.710189342 -1.479301453 1.358636856 0.027593607 -0.407812387 -0.166550234 0.897323072
1403638544977829376 -2.756323338 -1.482471228 1.375502825 0.027535452 -0.408702463 -0.166406736 0.896946430
1403638545027829504 -2.813000917 -1.493184686 1.378509641 0.027970102 -0.408929467 -0.165849298 0.896932781
1403638545077829376 -2.859966755 -1.503556609 1.385866165 0.028524213 -0.409320623 -0.165783063 0.896749139
1403638545127829504 -2.896048069 -1.502304912 1.404192209 0.029291118 -0.410244912 -0.165615439 0.896332920
1403638545177829376 -2.953545094 -1.506593823 1.402386665 0.028542388 -0.409669518 -0.166527376 0.896451235
1403638545227829504 -2.997400045 -1.506693602 1.408185244 0.027901376 -0.409407079 -0.167603984 0.896390676
1403638545277829376 -3.045244694 -1.505650163 1.430304050 0.029384663 -0.409993827 -0.168426707 0.895920813
1403638545327829504 -3.092063904 -1.512109280 1.433906555 0.030800074 -0.410171032 -0.168001011 0.895872056
1403638545377829376 -3.146002293 -1.511334777 1.454241276 0.033214565 -0.410654634 -0.166832536 0.895782590
1403638545427829504 -3.191886902 -1.516856790 1.475408673 0.031881873 -0.411626667 -0.166315183 0.895480990
1403638545477829376 -3.238284349 -1.508111477 1.478974462 0.031769991 -0.412906259 -0.166351959 0.894888818
1403638545527829504 -3.283289909 -1.502629161 1.495288253 0.031192461 -0.415979564 -0.167264417 0.893314421
1403638545577829376 -3.325735331 -1.503718972 1.501943827 0.029604372 -0.420332074 -0.169208571 0.890961826
1403638545627829504 -3.368661404 -1.497361422 1.508875489 0.029250596 -0.426719695 -0.170908287 0.887606382
1403638545677829376 -3.411587000 -1.494971991 1.512158155 0.028956678 -0.433574647 -0.174063683 0.883672118
1403638545727829504 -3.453717709 -1.503662109 1.528271317 0.026643099 -0.441616654 -0.177919462 0.878982067
1403638545777829376 -3.507764339 -1.508575320 1.532766342 0.026891649 -0.450341702 -0.182798654 0.873529553
1403638545827829504 -3.553859234 -1.512839317 1.540282488 0.027594520 -0.460293353 -0.187543690 0.867292285
1403638545877829376 -3.597825527 -1.519834042 1.545729399 0.026802223 -0.470538646 -0.192927554 0.860612571
1403638545927829504 -3.642280579 -1.529856205 1.550790548 0.027453624 -0.480911523 -0.199484944 0.853332400
1403638545977829376 -3.685758114 -1.542956352 1.555844665 0.026882377 -0.491316110 -0.205431044 0.845981061
1403638546027829504 -3.732945442 -1.554422855 1.551767468 0.027797475 -0.499385804 -0.211865783 0.839615405
1403638546077829376 -3.777259827 -1.563874125 1.564397454 0.029108880 -0.507266045 -0.217692196 0.833333015
1403638546127829504 -3.821418524 -1.578220844 1.569639206 0.029772114 -0.514223456 -0.221746609 0.827959120
1403638546177829376 -3.862300396 -1.584256411 1.565844536 0.029501600 -0.520560920 -0.223644495 0.823485970
1403638546227829504 -3.911498308 -1.594413996 1.580501795 0.028914465 -0.525588572 -0.225459501 0.819810092
1403638546277829376 -3.956717491 -1.599896431 1.583990216 0.028430229 -0.529341161 -0.227036163 0.816972673
1403638546327829504 -4.004297733 -1.604138017 1.591600180 0.026847703 -0.533304870 -0.226321891 0.814643204
1403638546377829376 -4.052485466 -1.608677030 1.601206660 0.025640223 -0.536146045 -0.225300416 0.813098848
1403638546427829504 -4.093738556 -1.610954642 1.598781347 0.023630541 -0.537734568 -0.224496409 0.812332749
1403638546477829376 -4.148469925 -1.611623764 1.617033482 0.023406483 -0.539155662 -0.224557549 0.811379850
1403638546527829504 -4.197322369 -1.611865759 1.624279737 0.023046037 -0.540171087 -0.225200012 0.810536265
1403638546577829376 -4.244537830 -1.610998631 1.634384871 0.023557514 -0.541887641 -0.226686358 0.808959901
1403638546627829504 -4.294114113 -1.615516901 1.636819363 0.023882143 -0.544713497 -0.228217006 0.806618750
1403638546677829376 -4.341565132 -1.619965196 1.641118288 0.024469027 -0.548061848 -0.229700089 0.803907573
1403638546727829504 -4.390187740 -1.625040889 1.643193007 0.024919422 -0.550989807 -0.231148258 0.801473498
1403638546777829376 -4.440123558 -1.633881092 1.650156021 0.025542457 -0.553307772 -0.233022958 0.799311221
1403638546827829504 -4.491215229 -1.643539429 1.652028203 0.026349507 -0.554980636 -0.235282585 0.797461152
1403638546877829376 -4.539757729 -1.654838085 1.655743361 0.026687095 -0.556519091 -0.236746162 0.795943201
1403638546927829504 -4.585021973 -1.658921003 1.654318452 0.027716080 -0.557231069 -0.238824829 0.794788063
1403638546977829376 -4.638481617 -1.672221899 1.660898447 0.029094985 -0.557769358 -0.241103679 0.793672383
1403638547027829504 -4.679743767 -1.673690796 1.665625811 0.030301617 -0.558365762 -0.242564023 0.792762399
1403638547077829376 -4.739402294 -1.682835460 1.665531993 0.031705815 -0.557963252 -0.244983181 0.792246819
1403638547127829504 -4.793255806 -1.687434793 1.665919304 0.033217948 -0.557149947 -0.247995302 0.791819990
1403638547177829376 -4.838106155 -1.686455131 1.670588017 0.033930082 -0.557145238 -0.249300018 0.791383266
1403638547227829504 -4.885623932 -1.685185552 1.671204805 0.034592424 -0.556609392 -0.250739813 0.791276753
1403638547277829376 -4.952330589 -1.689526439 1.673202038 0.035729326 -0.556192875 -0.251642734 0.791232467
1403638547327829504 -5.007027149 -1.689964771 1.672655582 0.035971586 -0.555838108 -0.252265960 0.791272283
1403638547377829376 -5.057563782 -1.684229136 1.674445391 0.033547714 -0.557492912 -0.247949973 0.791578829
1403638547427829504 -5.117831230 -1.682866931 1.673687696 0.030844418 -0.558094800 -0.245966032 0.791883528
1403638547477829376 -5.165357590 -1.678310513 1.675365567 0.028677696 -0.559393883 -0.242148161 0.792224884
1403638547527829504 -5.220469475 -1.668032646 1.671713114 0.026253508 -0.559721947 -0.239608750 0.792849123
1403638547577829376 -5.285811901 -1.666641235 1.665799022 0.024002217 -0.559706330 -0.238160893 0.793367624
1403638547627829504 -5.345498085 -1.658075094 1.670102596 0.023025276 -0.559915543 -0.236619681 0.793709993
1403638547677829376 -5.401339054 -1.647455812 1.669266462 0.022950709 -0.559355855 -0.236142427 0.794248700
1403638547727829504 -5.449822426 -1.639375210 1.668662071 0.023693429 -0.558395624 -0.237204269 0.794586122
1403638547777829376 -5.509373665 -1.625703216 1.671750307 0.024946855 -0.557929039 -0.238079831 0.794613659
1403638547827829504 -5.568737030 -1.614654779 1.668310165 0.027744714 -0.555934191 -0.241609678 0.794853568
1403638547877829376 -5.635610580 -1.598037720 1.672840357 0.029907165 -0.555898249 -0.241421297 0.794857502
1403638547927829504 -5.685569286 -1.587293386 1.676707029 0.028454389 -0.555956244 -0.241665617 0.794796050
1403638547977829376 -5.748260498 -1.578252912 1.669709444 0.029418258 -0.556213379 -0.241806135 0.794538260
1403638548027829504 -5.807424545 -1.569590569 1.664915919 0.027369361 -0.557592750 -0.241861105 0.793627441
1403638548077829376 -5.860068321 -1.559302092 1.666010976 0.026538013 -0.559989572 -0.242122054 0.791886628
1403638548127829504 -5.924239635 -1.554665804 1.654254436 0.026197622 -0.562594950 -0.242941320 0.789797544
1403638548177829376 -5.980421066 -1.551211119 1.655344963 0.025035981 -0.567041874 -0.244048744 0.786305845
1403638548227829504 -6.045967579 -1.543314099 1.646875858 0.025010649 -0.572147191 -0.244649142 0.782412231
1403638548277829376 -6.109042168 -1.540734172 1.631319761 0.023418374 -0.577185988 -0.247025013 0.778001666
1403638548327829504 -6.168738842 -1.547319293 1.620576978 0.023460507 -0.583701789 -0.248629197 0.772609413
1403638548377829376 -6.231068611 -1.550576210 1.606918097 0.022674814 -0.590057313 -0.252578497 0.766499996
1403638548427829504 -6.294777870 -1.542011499 1.603794694 0.022567166 -0.597138822 -0.254374176 0.760401011
1403638548477829376 -6.335742950 -1.564158201 1.584509611 0.022165278 -0.603117466 -0.256764144 0.754870951
1403638548527829504 -6.399065018 -1.566610217 1.573548794 0.021873569 -0.608483076 -0.258152932 0.750084639
1403638548577829376 -6.468913078 -1.565922379 1.561310053 0.022676870 -0.613215148 -0.259489745 0.745733261
1403638548627829504 -6.539780617 -1.561546326 1.536292791 0.022958085 -0.616438508 -0.261009455 0.742529809
1403638548677829376 -6.610774517 -1.581927180 1.518261671 0.021618882 -0.619687557 -0.262186348 0.739444613
1403638548727829504 -6.659562588 -1.577454090 1.510670662 0.022289680 -0.622194290 -0.263339818 0.736905396
1403638548777829376 -6.740997314 -1.577932596 1.495676041 0.021908388 -0.624386132 -0.263921350 0.734852016
1403638548827829504 -6.808285236 -1.559010506 1.483023524 0.022207037 -0.626093030 -0.263812363 0.733428597
1403638548877829376 -6.879605293 -1.565908909 1.488715172 0.022194151 -0.627826095 -0.264338851 0.731755912
1403638548927829504 -6.932656288 -1.562035441 1.497105002 0.022790976 -0.630142629 -0.263272047 0.730129242
1403638548977829376 -7.006625652 -1.557426691 1.484851241 0.023026017 -0.630648315 -0.263268232 0.729686499
1403638549027829504 -7.062854767 -1.579505563 1.463067412 0.022337822 -0.630083084 -0.265368640 0.729435265
1403638549077829376 -7.132345200 -1.577900052 1.446374059 0.022330005 -0.630729854 -0.263532579 0.729542136
1403638549127829504 -7.220908165 -1.582830667 1.408440709 0.022231504 -0.631465375 -0.261840135 0.729518294
1403638549177829376 -7.290097237 -1.607043266 1.390576124 0.022426413 -0.631497502 -0.261722326 0.729526818
1403638549227829504 -7.374141216 -1.623111010 1.363562703 0.022141315 -0.631323278 -0.261956155 0.729602396
1403638549277829376 -7.436325073 -1.634952784 1.351799726 0.021154841 -0.630822539 -0.260860562 0.730456829
1403638549327829504 -7.505414963 -1.649386406 1.329064608 0.020410916 -0.631099939 -0.259435654 0.730745792
1403638549377829376 -7.572022915 -1.666377068 1.306751728 0.020059654 -0.631203294 -0.257937670 0.731196404
1403638549427829504 -7.611726284 -1.681496620 1.315713048 0.019833671 -0.632516086 -0.255583256 0.730894804
1403638549477829376 -7.714910507 -1.686031580 1.273847699 0.018519005 -0.631859601 -0.254016548 0.732042372
1403638549527829504 -7.786763191 -1.698793888 1.258309126 0.018389812 -0.631899655 -0.253233016 0.732282460
1403638549577829376 -7.857046604 -1.705804825 1.243008256 0.019557284 -0.632229388 -0.251216292 0.732662201
1403638549627829504 -7.926142216 -1.711977959 1.224057555 0.020964434 -0.632364988 -0.249873400 0.732965410
1403638549677829376 -8.000000954 -1.724822760 1.210346580 0.021383988 -0.632449925 -0.249133572 0.733131766
1403638549727829504 -8.067770958 -1.733048916 1.196542144 0.023066234 -0.631564319 -0.250591725 0.733347297
1403638549777829376 -8.143486977 -1.746830463 1.180701137 0.021565566 -0.631625354 -0.250559479 0.733351409
1403638549827829504 -8.211310387 -1.758981228 1.164323211 0.020548504 -0.631591618 -0.250234753 0.733520508
1403638549877829376 -8.272780418 -1.773014784 1.157058835 0.019571615 -0.631223321 -0.250620425 0.733732522
1403638549927829504 -8.348558426 -1.787305355 1.135420799 0.019876638 -0.630620599 -0.251455605 0.733956814
1403638549977829376 -8.424124718 -1.804612160 1.114828348 0.018522648 -0.630747914 -0.250883669 0.734078586
1403638550027829504 -8.494714737 -1.824290514 1.099067450 0.018286560 -0.630856097 -0.250360370 0.734170198
1403638550077829376 -8.563991547 -1.848232985 1.082800865 0.017868711 -0.631053150 -0.250327617 0.734022260
1403638550127829504 -8.625886917 -1.870541096 1.072844267 0.016421732 -0.632035494 -0.248951823 0.733678699
1403638550177829376 -8.708451271 -1.892118454 1.048085690 0.016681191 -0.631708324 -0.249308884 0.733833373
1403638550227829504 -8.777387619 -1.920065880 1.030609131 0.016273372 -0.631974816 -0.249737144 0.733467340
1403638550277829376 -8.850120544 -1.941557407 1.010226727 0.017159306 -0.631767809 -0.249871448 0.733579695
1403638550327829504 -8.922440529 -1.971632957 0.994409800 0.017505705 -0.631905794 -0.250480145 0.733245015
1403638550377829376 -8.989085197 -1.996929169 0.980783045 0.018496299 -0.632235169 -0.250244707 0.733017147
1403638550427829504 -9.063915253 -2.025505066 0.960772872 0.017878838 -0.633082688 -0.248672679 0.732835948
1403638550477829376 -9.136695862 -2.048815727 0.946894526 0.017063566 -0.633662879 -0.247400835 0.732784390
1403638550527829504 -9.202696800 -2.075465202 0.936856449 0.015576861 -0.634700358 -0.245925277 0.732416272
1403638550577829376 -9.276819229 -2.095381737 0.918645918 0.015855299 -0.635533988 -0.243182808 0.732603073
1403638550627829504 -9.342837334 -2.131652355 0.918118894 0.016375832 -0.637224436 -0.241197452 0.731779039
1403638550677829376 -9.421984673 -2.140195131 0.897748411 0.018722607 -0.637681007 -0.237630159 0.732491851
1403638550727829504 -9.492581367 -2.158830404 0.887244642 0.019141851 -0.638437331 -0.235647008 0.732462883
1403638550777829376 -9.563672066 -2.185785532 0.882807314 0.020125043 -0.638981223 -0.234569162 0.732308149
1403638550827829504 -9.634787560 -2.203407526 0.875648737 0.023313971 -0.639868975 -0.231577218 0.732390702
1403638550877829376 -9.708941460 -2.218605042 0.864217222 0.027097227 -0.640990973 -0.227576062 0.732533574
1403638550927829504 -9.769718170 -2.233520746 0.867089689 0.031583056 -0.642175853 -0.223682314 0.732515454
1403638550977829376 -9.832249641 -2.250854492 0.868291199 0.034672286 -0.643727720 -0.220065579 0.732108951
1403638551027829504 -9.910939217 -2.266895771 0.859255195 0.037423700 -0.644157767 -0.217879221 0.732249200
1403638551077829376 -9.961155891 -2.281733990 0.867283344 0.039915029 -0.645382702 -0.216102287 0.731565297
1403638551127829504 -10.021795273 -2.306379557 0.867282331 0.038909134 -0.646143198 -0.214725226 0.731353581
1403638551177829376 -10.100847244 -2.324724913 0.859921992 0.038150687 -0.647162735 -0.211630702 0.731394112
1403638551227829504 -10.160612106 -2.342261076 0.853693604 0.037337996 -0.647427142 -0.210392356 0.731559277
1403638551277829376 -10.216174126 -2.365475178 0.856923342 0.035881627 -0.647138476 -0.209873050 0.732036650
1403638551327829504 -10.272172928 -2.386526823 0.855962813 0.033170559 -0.644876897 -0.210679606 0.733926117
1403638551377829376 -10.321947098 -2.411912918 0.864992976 0.029918920 -0.641996086 -0.209480584 0.736928582
1403638551427829504 -10.373168945 -2.431622744 0.867571890 0.027128331 -0.636776745 -0.207782567 0.742028177
1403638551477829376 -10.425083160 -2.456059456 0.876301408 0.024160178 -0.630711317 -0.205428615 0.747942865
1403638551527829504 -10.475334167 -2.476261616 0.881732464 0.021105969 -0.623566926 -0.200940430 0.755209744
1403638551577829376 -10.523454666 -2.498458385 0.895589352 0.019501898 -0.616222084 -0.195106775 0.762773514
1403638551627829504 -10.579383850 -2.525286913 0.905091047 0.015059746 -0.608168602 -0.189434320 0.770726085
1403638551677829376 -10.616505623 -2.542490721 0.924185753 0.012819176 -0.600371122 -0.183379024 0.778307319
1403638551727829504 -10.670283318 -2.556962252 0.934156656 0.012525195 -0.590896308 -0.177733868 0.786826134
1403638551777829376 -10.709847450 -2.573429108 0.958097219 0.012060639 -0.581831992 -0.172323376 0.794752002
1403638551827829504 -10.752387047 -2.587303877 0.974960089 0.012434560 -0.572585046 -0.167367965 0.802483499
1403638551877829376 -10.791622162 -2.609206676 1.003015518 0.014460803 -0.564470053 -0.164852694 0.808695257
1403638551927829504 -10.829194069 -2.626096487 1.029223442 0.018740738 -0.556535244 -0.164780810 0.814103484
1403638551977829376 -10.874215126 -2.647253513 1.048333406 0.023385517 -0.549471438 -0.164650589 0.818794489
1403638552027829504 -10.911396027 -2.673766613 1.072636127 0.028233984 -0.542862236 -0.165223554 0.822924435
1403638552077829376 -10.940194130 -2.702522278 1.100979805 0.031457927 -0.538177788 -0.165894732 0.825744510
1403638552127829504 -10.975946426 -2.728119850 1.127570629 0.031658068 -0.534047365 -0.166558206 0.828281105
1403638552177829376 -11.003847122 -2.748055458 1.154823780 0.029972691 -0.531480193 -0.165514395 0.830202043
1403638552227829504 -11.036592484 -2.786556005 1.179578781 0.028034141 -0.528968036 -0.167176157 0.831540167
1403638552277829376 -11.065703392 -2.818427086 1.204442501 0.026341936 -0.527108550 -0.167395040 0.832731366
1403638552327829504 -11.087585449 -2.855372429 1.235483408 0.025514169 -0.526634395 -0.167017475 0.833132863
1403638552377829376 -11.116032600 -2.879690647 1.268758059 0.025904585 -0.527529955 -0.163397878 0.833271980
1403638552427829504 -11.143260956 -2.919694901 1.293453693 0.028976448 -0.528173864 -0.159551844 0.833508193
1403638552477829376 -11.165925980 -2.943210602 1.328305244 0.032238308 -0.529936135 -0.154800192 0.833165824
1403638552527829504 -11.187591553 -2.980254650 1.358444691 0.034953468 -0.530822217 -0.151756719 0.833052158
1403638552577829376 -11.208009720 -3.003978014 1.390849352 0.038158026 -0.531745195 -0.149248719 0.832776010
1403638552627829504 -11.229393005 -3.023943186 1.428183317 0.040520888 -0.532342374 -0.148101762 0.832487583
1403638552677829376 -11.247270584 -3.054553509 1.465153217 0.041079395 -0.532492280 -0.149686858 0.832080662
1403638552727829504 -11.258924484 -3.072876453 1.507040501 0.041101564 -0.533120096 -0.149597496 0.831693590
1403638552777829376 -11.266933441 -3.104422331 1.548978329 0.040912934 -0.533402801 -0.151588067 0.831160963
1403638552827829504 -11.281740189 -3.124478340 1.582784176 0.041464683 -0.533194721 -0.153171808 0.830976784
1403638552877829376 -11.292407990 -3.150943756 1.623443604 0.041770961 -0.532841980 -0.156501621 0.830567181
1403638552927829504 -11.290273666 -3.171057701 1.672398567 0.041867830 -0.533241570 -0.160131484 0.829613388
1403638552977829376 -11.296464920 -3.189036369 1.711553574 0.043966733 -0.532559156 -0.163642123 0.829258084
1403638553027829504 -11.307056427 -3.203112602 1.747845650 0.044562057 -0.531333089 -0.167682439 0.829205632
1403638553077829376 -11.305677414 -3.223493814 1.801130533 0.046106402 -0.532001674 -0.170136899 0.828191936
1403638553127829504 -11.302267075 -3.241638184 1.847640753 0.047544368 -0.533616722 -0.169208363 0.827261269
1403638553177829376 -11.304765701 -3.258363247 1.885222435 0.050549082 -0.535098791 -0.165882736 0.826799214
1403638553227829504 -11.302036285 -3.274799585 1.931056499 0.054462701 -0.537330508 -0.161808744 0.825910211
1403638553277829376 -11.297451973 -3.295834541 1.974971056 0.058501821 -0.538961887 -0.159317955 0.825054765
1403638553327829504 -11.290846825 -3.311711311 2.017002583 0.062671453 -0.539891362 -0.157875970 0.824417830
1403638553377829376 -11.280116081 -3.334558010 2.057063818 0.065628543 -0.540001810 -0.159213364 0.823858023
1403638553427829504 -11.266388893 -3.356609344 2.102877140 0.070370734 -0.539329827 -0.161645919 0.823432922
1403638553477829376 -11.254915237 -3.373179674 2.136036634 0.074418306 -0.538021326 -0.163988665 0.823469877
1403638553527829504 -11.237556458 -3.397633791 2.179390907 0.077559859 -0.537751794 -0.165957689 0.822961450
1403638553577829376 -11.220968246 -3.419253826 2.205671310 0.081108630 -0.535995543 -0.167921796 0.823366523
1403638553627829504 -11.201072693 -3.444197178 2.227648735 0.082244106 -0.534499705 -0.169903651 0.823819637
1403638553677829376 -11.171676636 -3.470227242 2.269426823 0.082556270 -0.534464180 -0.170957863 0.823593259
1403638553727829504 -11.143274307 -3.505210876 2.302729368 0.082096055 -0.534338474 -0.172219425 0.823458016
1403638553777829376 -11.112464905 -3.523746490 2.327607870 0.082017876 -0.533396780 -0.173630089 0.823780060
1403638553827829504 -11.081178665 -3.551620007 2.352198362 0.080721997 -0.532334507 -0.174398527 0.824432552
1403638553877829376 -11.042583466 -3.583966732 2.383219242 0.079397507 -0.532078266 -0.175549582 0.824482322
1403638553927829504 -11.004667282 -3.608707428 2.395646334 0.078453250 -0.530515611 -0.176745445 0.825323761
1403638553977829376 -10.968944550 -3.634304523 2.411001682 0.075268701 -0.529953241 -0.176504806 0.826032877
1403638554027829504 -10.929997444 -3.666574955 2.451366186 0.070842862 -0.530879140 -0.176221624 0.825890183
1403638554077829376 -10.888233185 -3.685190439 2.469333410 0.069989413 -0.529733300 -0.178246573 0.826264024
1403638554127829504 -10.845108032 -3.707556725 2.484491348 0.068422377 -0.528743982 -0.178887859 0.826890171
1403638554177829376 -10.801987648 -3.733260393 2.517459631 0.064718597 -0.527422488 -0.183643520 0.826989770
1403638554227829504 -10.755137444 -3.758786678 2.536202431 0.058460835 -0.525528252 -0.188558266 0.827555478
1403638554277829376 -10.716360092 -3.772358418 2.557527304 0.054040425 -0.523526430 -0.192790359 0.828149498
1403638554327829504 -10.665724754 -3.777517080 2.573630810 0.051940724 -0.521533906 -0.196509913 0.828666627
1403638554377829376 -10.622316360 -3.804862261 2.607360363 0.048323847 -0.521161497 -0.199880958 0.828313410
1403638554427829504 -10.579877853 -3.812832355 2.619414091 0.046646755 -0.519534588 -0.201055735 0.829146862
1403638554477829376 -10.530986786 -3.826938152 2.656933546 0.045882050 -0.519958675 -0.202830702 0.828491092
1403638554527829504 -10.487676620 -3.847970247 2.666251659 0.044375427 -0.519479215 -0.203473017 0.828716397
1403638554577829376 -10.440674782 -3.855415583 2.686506271 0.043847956 -0.519885182 -0.202492341 0.828730106
1403638554627829504 -10.397905350 -3.868204594 2.727348804 0.041653585 -0.521509349 -0.200205207 0.828378439
1403638554677829376 -10.354180336 -3.881412983 2.746688128 0.039804455 -0.523240805 -0.195393398 0.828526437
1403638554727829504 -10.312255859 -3.891805887 2.765820980 0.040560938 -0.523535371 -0.193770379 0.828684807
1403638554777829376 -10.271238327 -3.911681890 2.784073591 0.038698133 -0.525115311 -0.189949691 0.828658819
1403638554827829504 -10.227937698 -3.923003674 2.795681477 0.039033864 -0.525048494 -0.188809633 0.828945935
1403638554877829376 -10.186929703 -3.945446014 2.818450928 0.038821381 -0.525985837 -0.186584145 0.828865588
1403638554927829504 -10.149316788 -3.966450214 2.843197346 0.038788289 -0.526762903 -0.185139149 0.828697681
1403638554977829376 -10.103017807 -3.986629486 2.858564377 0.038706716 -0.525967240 -0.182622358 0.829764605
1403638555027829504 -10.061058044 -4.004957676 2.874396324 0.039044734 -0.523466527 -0.181441844 0.831587136
1403638555077829376 -10.019185066 -4.019132614 2.893704653 0.038878880 -0.519510388 -0.181281641 0.834106922
1403638555127829504 -9.977513313 -4.032013893 2.925680161 0.039444253 -0.515188515 -0.180759758 0.836869657
1403638555177829376 -9.929925919 -4.047971725 2.939694881 0.037748583 -0.509769380 -0.178864524 0.840665042
1403638555227829504 -9.886086464 -4.059944630 2.958329678 0.037817199 -0.504304111 -0.177042022 0.844336033
1403638555277829376 -9.848949432 -4.074160099 2.975441217 0.036843624 -0.498370141 -0.175374597 0.848241448
1403638555327829504 -9.801548958 -4.087551117 3.015007019 0.036561154 -0.494605392 -0.173880354 0.850761116
1403638555377829376 -9.761819839 -4.099284649 3.050575733 0.038439292 -0.490471035 -0.175093040 0.852820635
1403638555427829504 -9.707550049 -4.100440502 3.061707497 0.039788038 -0.485853612 -0.175653026 0.855283082
1403638555477829376 -9.668029785 -4.114697456 3.103351593 0.040702019 -0.483378530 -0.175898120 0.856591165
1403638555527829504 -9.621370316 -4.118265629 3.127673149 0.040644590 -0.481465697 -0.174179047 0.858021259
1403638555577829376 -9.578719139 -4.124397278 3.167800903 0.042243585 -0.479977101 -0.174574569 0.858697355
1403638555627829504 -9.533460617 -4.134848118 3.186201096 0.041408349 -0.478648216 -0.174193174 0.859556854
1403638555677829376 -9.492919922 -4.141475677 3.204161167 0.041109726 -0.477316737 -0.173909187 0.860368729
1403638555727829504 -9.454842567 -4.157343388 3.239450455 0.039554637 -0.477319390 -0.172682330 0.860687196
1403638555777829376 -9.412246704 -4.172068119 3.250900507 0.038927045 -0.475691974 -0.174096450 0.861331642
1403638555827829504 -9.371530533 -4.191936970 3.273446083 0.038320053 -0.475258529 -0.174789160 0.861457884
1403638555877829376 -9.330596924 -4.211665630 3.306930542 0.037199616 -0.475709975 -0.174694374 0.861276984
1403638555927829504 -9.288344383 -4.234276295 3.334814787 0.037454620 -0.475820839 -0.176014498 0.860935867
1403638555977829376 -9.243555069 -4.261230946 3.358406067 0.038718063 -0.475849777 -0.177660108 0.860525846
1403638556027829504 -9.193229675 -4.276278973 3.347637415 0.039495349 -0.473897427 -0.178108782 0.861474633
1403638556077829376 -9.155641556 -4.299667358 3.366484880 0.038295865 -0.473001510 -0.178886265 0.861860037
1403638556127829504 -9.110638618 -4.325662613 3.387190104 0.034896705 -0.473279655 -0.179250285 0.861775994
1403638556177829376 -9.072341919 -4.348392010 3.417360067 0.029951880 -0.473088890 -0.179504380 0.862013876
1403638556227829504 -9.039204597 -4.361690998 3.476702690 0.027981928 -0.474161983 -0.181212336 0.861132681
1403638556277829376 -8.995899200 -4.384366989 3.469951868 0.024278264 -0.472401589 -0.181123063 0.862230659
1403638556327829504 -8.956295967 -4.392086029 3.499763489 0.023489930 -0.472090185 -0.182265863 0.862182260
1403638556377829376 -8.912897110 -4.411818027 3.530442715 0.021754138 -0.472299457 -0.182747364 0.862011194
1403638556427829504 -8.877565384 -4.422556877 3.545989990 0.020115804 -0.471369058 -0.182818845 0.862544954
1403638556477829376 -8.844110489 -4.453955650 3.592200756 0.015232054 -0.471323937 -0.184172958 0.862381577
1403638556527829504 -8.806338310 -4.458924294 3.627681732 0.013964552 -0.470989496 -0.184881911 0.862434089
1403638556577829376 -8.771248817 -4.482481956 3.661628008 0.011456117 -0.471436173 -0.184308618 0.862349689
1403638556627829504 -8.744384766 -4.492944717 3.693456650 0.009698807 -0.472714663 -0.179742143 0.862635255
1403638556677829376 -8.723197937 -4.525378227 3.712209940 0.006781177 -0.473581374 -0.175051808 0.863152087
1403638556727829504 -8.689000130 -4.546147346 3.739041328 0.009813047 -0.474783510 -0.170634001 0.863347173
1403638556777829376 -8.648323059 -4.579229355 3.766351461 0.012779585 -0.475742757 -0.167326808 0.863427639
1403638556827829504 -8.630292892 -4.606855869 3.796479464 0.014515614 -0.475965649 -0.163608328 0.863989770
1403638556877829376 -8.600292206 -4.642301083 3.833576679 0.014805979 -0.477417052 -0.160513267 0.863764584
1403638556927829504 -8.570748329 -4.673892021 3.868320942 0.016475597 -0.478426307 -0.158192590 0.863604069
1403638556977829376 -8.538915634 -4.696396351 3.908921719 0.018393459 -0.479111642 -0.156625912 0.863470912
1403638557027829504 -8.509246826 -4.735968113 3.940291882 0.018069927 -0.478617787 -0.156850070 0.863710940
1403638557077829376 -8.482570648 -4.743182182 3.987212896 0.021855678 -0.478404164 -0.158784389 0.863388300
1403638557127829504 -8.448751450 -4.770768642 4.039369583 0.023415111 -0.478982478 -0.160204560 0.862764180
1403638557177829376 -8.423590660 -4.800885201 4.084903240 0.024152596 -0.478756845 -0.160888016 0.862741888
1403638557227829504 -8.398546219 -4.840070248 4.144509315 0.024146697 -0.479634643 -0.162629604 0.861927569
1403638557277829376 -8.366592407 -4.861607552 4.195128441 0.024318257 -0.479802907 -0.162150353 0.861919403
1403638557327829504 -8.335316658 -4.871682644 4.230949402 0.026612431 -0.478520155 -0.163272515 0.862352788
1403638557377829376 -8.314891815 -4.897730350 4.283692837 0.026802540 -0.478030354 -0.165283367 0.862235487
1403638557427829504 -8.286852837 -4.930170536 4.314318657 0.028265148 -0.475985348 -0.168025896 0.862789869
1403638557477829376 -8.270249367 -4.940462112 4.385265350 0.032379832 -0.475243419 -0.172365665 0.862197936
1403638557527829504 -8.235340118 -4.967356205 4.435789585 0.034158316 -0.474401206 -0.174477294 0.862168431
1403638557577829376 -8.220203400 -4.991394997 4.480715275 0.036570709 -0.472905338 -0.176781252 0.862421870
1403638557627829504 -8.175289154 -5.016013622 4.508196354 0.038755987 -0.471992373 -0.178716049 0.862427831
1403638557677829376 -8.150540352 -5.028023720 4.546064377 0.041307442 -0.470546812 -0.179196164 0.862999499
1403638557727829504 -8.126143456 -5.078618050 4.597282887 0.039511789 -0.470668375 -0.179331079 0.862989247
1403638557777829376 -8.098389626 -5.101860046 4.649838448 0.041233864 -0.471034199 -0.180169523 0.862534344
1403638557827829504 -8.065123558 -5.129793644 4.678250313 0.042094477 -0.469089687 -0.181896284 0.863189816
1403638557877829376 -8.041990280 -5.162986279 4.741393089 0.040559009 -0.470243126 -0.182094604 0.862593710
1403638557927829504 -8.016257286 -5.193511486 4.775462151 0.039621588 -0.468216985 -0.184043065 0.863325596
1403638557977829376 -7.987445831 -5.214205265 4.824422836 0.038573835 -0.468323380 -0.185369998 0.863031447
1403638558027829504 -7.963111401 -5.232059479 4.876947403 0.036141433 -0.468515575 -0.185515210 0.863001168
1403638558077829376 -7.942364216 -5.248179913 4.929539680 0.032722119 -0.468611240 -0.185927808 0.862996876
1403638558127829504 -7.913264751 -5.264408112 4.970376492 0.027407408 -0.468074113 -0.186212361 0.863412023
1403638558177829376 -7.900911331 -5.299384594 5.026806831 0.020823753 -0.467225283 -0.188955814 0.863459647
1403638558227829504 -7.864705563 -5.313906193 5.054186821 0.016423194 -0.465073258 -0.188777670 0.864754379
1403638558277829376 -7.847436905 -5.329360962 5.083294868 0.015198103 -0.463374823 -0.190708429 0.865264773
1403638558327829504 -7.834220886 -5.352671146 5.126958370 0.014065165 -0.461942255 -0.194042116 0.865308702
1403638558377829376 -7.824319839 -5.378540039 5.168227196 0.013125468 -0.459732771 -0.196974114 0.865837574
1403638558427829504 -7.799069405 -5.401538849 5.211788177 0.010214489 -0.458407879 -0.199619845 0.865973294
1403638558477829376 -7.794796944 -5.436091900 5.253273487 0.006359854 -0.456323624 -0.203332841 0.866247118
1403638558527829504 -7.781352043 -5.461520672 5.306152344 0.005346449 -0.456971258 -0.202997759 0.865991116
1403638558577829376 -7.779738426 -5.500234127 5.356901169 0.002936444 -0.458002239 -0.201157287 0.865887463
1403638558627829504 -7.764054775 -5.534760475 5.396731853 0.003549043 -0.459447533 -0.196396038 0.866212428
1403638558677829376 -7.770474911 -5.577287674 5.436712742 0.001927654 -0.460681617 -0.190093473 0.866967857
1403638558727829504 -7.762891293 -5.612657070 5.478796005 0.003979289 -0.462945461 -0.183926299 0.867085218
1403638558777829376 -7.771574497 -5.638958931 5.531303406 0.005584515 -0.464181513 -0.179974422 0.867244840
1403638558827829504 -7.792385101 -5.661230564 5.562193871 0.007780578 -0.462699056 -0.177465245 0.868536234
1403638558877829376 -7.791761398 -5.697128773 5.600658417 0.009487543 -0.461966485 -0.177289709 0.868944943
1403638558927829504 -7.783285141 -5.738953590 5.660837650 0.012863510 -0.463547051 -0.177048683 0.868108511
1403638558977829376 -7.782864571 -5.775890350 5.704486847 0.018107740 -0.463860214 -0.176630661 0.867932856
1403638559027829504 -7.779750824 -5.823562622 5.763628006 0.020195860 -0.464679956 -0.176652968 0.867443562
1403638559077829376 -7.777482033 -5.858417511 5.797527313 0.023237756 -0.464200437 -0.176586851 0.867637634
1403638559127829504 -7.779624462 -5.893428802 5.861559868 0.027086217 -0.463796258 -0.175766051 0.867908776
1403638559177829376 -7.787105560 -5.925853252 5.917755604 0.029422188 -0.463749528 -0.176394954 0.867730081
1403638559227829504 -7.797936440 -5.947471142 5.968325138 0.032201480 -0.462549508 -0.178332463 0.867875874
1403638559277829376 -7.793866158 -5.967852592 6.025455475 0.034634382 -0.462577850 -0.178531766 0.867726088
1403638559327829504 -7.793000221 -6.012129307 6.095052719 0.034757983 -0.464284360 -0.182284757 0.866027832
1403638559377829376 -7.799407005 -6.032275677 6.152578831 0.036705900 -0.463204294 -0.184828207 0.865986705
1403638559427829504 -7.809563160 -6.039562225 6.199327946 0.040433276 -0.461045206 -0.186778039 0.866554379
1403638559477829376 -7.821841717 -6.066266537 6.267553329 0.040875010 -0.461625069 -0.188487038 0.865854621
1403638559527829504 -7.824242592 -6.090400696 6.307835102 0.042681828 -0.460287839 -0.189825848 0.866186738
1403638559577829376 -7.831719875 -6.108716965 6.366548061 0.043916442 -0.460547537 -0.190847293 0.865762413
1403638559627829504 -7.836348534 -6.125086308 6.442376614 0.044720527 -0.462537855 -0.189256430 0.865009129
1403638559677829376 -7.848684311 -6.141795635 6.491901398 0.045043848 -0.461820036 -0.189693883 0.865280032
1403638559727829504 -7.858194828 -6.148604870 6.531849861 0.047144338 -0.461046755 -0.190416425 0.865421772
1403638559777829376 -7.869352818 -6.168738842 6.594212055 0.046879206 -0.462427884 -0.190253362 0.864734888
1403638559827829504 -7.881008148 -6.185194969 6.636215210 0.046026442 -0.461792856 -0.190476269 0.865070939
1403638559877829376 -7.871889591 -6.231875896 6.697918415 0.043125611 -0.464860320 -0.188964441 0.863908291
1403638559927829504 -7.890920639 -6.233235836 6.771057129 0.043671362 -0.464673042 -0.185558915 0.864719391
1403638559977829376 -7.909409523 -6.251894951 6.799291611 0.043503936 -0.458415359 -0.183355421 0.868529499
1403638560027829504 -7.919011593 -6.266879559 6.853374481 0.043205835 -0.454005837 -0.179562330 0.871647418
1403638560077829376 -7.932722092 -6.286510468 6.901127815 0.041986912 -0.446271211 -0.175104246 0.876594305
1403638560127829504 -7.954984665 -6.301311493 6.941036224 0.042040065 -0.435495824 -0.171336427 0.882734299
1403638560177829376 -7.957839012 -6.313953400 6.997889519 0.042822659 -0.426878512 -0.166361243 0.887842834
1403638560227829504 -7.967892647 -6.331696510 7.052257538 0.041595656 -0.415748358 -0.160626844 0.894215941
1403638560277829376 -7.974356651 -6.344285965 7.100917816 0.043102078 -0.403953165 -0.155332655 0.900464237
1403638560327829504 -7.985492229 -6.344241619 7.154605389 0.047615781 -0.392119348 -0.148338333 0.906626105
1403638560377829376 -7.992724895 -6.357243061 7.217924595 0.050287142 -0.381810486 -0.140813515 0.912065506
1403638560427829504 -8.008449554 -6.359124660 7.273280144 0.053220749 -0.368827909 -0.132639796 0.918444455
1403638560477829376 -8.013818741 -6.369409561 7.329222679 0.055650041 -0.356917441 -0.125022650 0.924057543
1403638560527829504 -8.027536392 -6.375262737 7.383915424 0.056883637 -0.344099373 -0.117506973 0.929812849
1403638560577829376 -8.032735825 -6.375346661 7.429581165 0.057786405 -0.331201375 -0.108226843 0.935549736
1403638560627829504 -8.052588463 -6.371152401 7.486150742 0.058024101 -0.318274111 -0.099377654 0.940988243
1403638560677829376 -8.054284096 -6.375380516 7.532624722 0.057039570 -0.306538016 -0.090554029 0.945822835
1403638560727829504 -8.062295914 -6.376827240 7.583251953 0.055359114 -0.296557277 -0.080316558 0.950020194
1403638560777829376 -8.068074226 -6.383088112 7.628332138 0.055066209 -0.285549074 -0.073355444 0.953964591
1403638560827829504 -8.073153496 -6.386977673 7.680131435 0.055534270 -0.274175107 -0.067281336 0.957714558
1403638560877829376 -8.068671227 -6.396154881 7.722572327 0.056181729 -0.263765246 -0.060208246 0.961065292
1403638560927829504 -8.067731857 -6.406565189 7.766575813 0.056863543 -0.252613574 -0.054142971 0.964376211
1403638560977829376 -8.073801041 -6.410042763 7.816141605 0.059977971 -0.240849867 -0.049159441 0.967459202
1403638561027829504 -8.053956985 -6.421899796 7.845052242 0.063416131 -0.230497077 -0.044547595 0.969981968
1403638561077829376 -8.052656174 -6.434575081 7.889777184 0.064963229 -0.219182223 -0.039123673 0.972732365
1403638561127829504 -8.041905403 -6.447908878 7.927278042 0.067821346 -0.208890870 -0.034689464 0.974967480
1403638561177829376 -8.035322189 -6.460935593 7.967469692 0.070261866 -0.199467972 -0.030631224 0.976902008
1403638561227829504 -8.023519516 -6.475745678 8.001461983 0.072529562 -0.191476211 -0.026872370 0.978444755
1403638561277829376 -8.000625610 -6.494330406 8.031560898 0.074615143 -0.186023429 -0.023174897 0.979433894
1403638561327829504 -7.987525463 -6.508625507 8.064202309 0.073538527 -0.180368170 -0.021467065 0.980611324
1403638561377829376 -7.969824791 -6.519015789 8.095865250 0.070108511 -0.175313085 -0.023371181 0.981735110
1403638561427829504 -7.942196846 -6.535769463 8.116886139 0.065629512 -0.170680121 -0.028448248 0.982726693
1403638561477829376 -7.913559914 -6.548841476 8.141283035 0.061361026 -0.166652218 -0.033938631 0.983519197
1403638561527829504 -7.891246796 -6.554069996 8.171581268 0.058876593 -0.163264200 -0.038755581 0.984061122
1403638561577829376 -7.871890068 -6.563491821 8.194353104 0.055875219 -0.160771698 -0.042996917 0.984470248
1403638561627829504 -7.847566605 -6.560860634 8.223402023 0.054584730 -0.159260020 -0.045532506 0.984674335
1403638561677829376 -7.826627731 -6.564089775 8.250290871 0.053609058 -0.159028560 -0.046957202 0.984698474
1403638561727829504 -7.797747612 -6.568812847 8.275604248 0.052641198 -0.159266219 -0.048083905 0.984657884
1403638561777829376 -7.773351669 -6.573924065 8.294909477 0.052388206 -0.159212872 -0.049420740 0.984613776
1403638561827829504 -7.751300335 -6.567953587 8.325841904 0.053303972 -0.158801690 -0.050315380 0.984585762
1403638561877829376 -7.731293678 -6.564408302 8.352895737 0.054494463 -0.157021523 -0.051060699 0.984767735
1403638561927829504 -7.696579933 -6.567040920 8.379500389 0.054111488 -0.154450789 -0.051967129 0.985147834
1403638561977829376 -7.669095039 -6.564662457 8.402043343 0.054214485 -0.150684223 -0.050539341 0.985799611
1403638562027829504 -7.652757168 -6.558813572 8.427103043 0.054468561 -0.145198837 -0.048758745 0.986698091
1403638562077829376 -7.619880676 -6.559668064 8.451547623 0.054235946 -0.139346376 -0.047112450 0.987634301
1403638562127829504 -7.603634834 -6.555132866 8.472867966 0.054380830 -0.132832065 -0.044463161 0.988646269
1403638562177829376 -7.577845573 -6.550171852 8.491965294 0.054754328 -0.127116978 -0.042785212 0.989450693
1403638562227829504 -7.537295341 -6.556182861 8.515571594 0.055132613 -0.122778147 -0.041316848 0.990039825
1403638562277829376 -7.502663136 -6.559439659 8.533051491 0.055221565 -0.118045673 -0.039402422 0.990688264
1403638562327829504 -7.489441872 -6.564040184 8.550304413 0.056041501 -0.111944452 -0.036554452 0.991459310
1403638562377829376 -7.456898689 -6.561911106 8.561052322 0.057305086 -0.105872117 -0.032797247 0.992185235
1403638562427829504 -7.438675880 -6.568266869 8.580633163 0.057310473 -0.098061912 -0.028638035 0.993115902
1403638562477829376 -7.424637794 -6.572615623 8.579442978 0.056894105 -0.089475334 -0.023560207 0.994083583
1403638562527829504 -7.389944077 -6.573925018 8.600584030 0.056839783 -0.080183223 -0.018337278 0.994989276
1403638562577829376 -7.361313820 -6.585896969 8.616339684 0.057306942 -0.070572689 -0.011981810 0.995787024
1403638562627829504 -7.337784767 -6.595360756 8.619243622 0.057386804 -0.060550719 -0.004434064 0.996504247
1403638562677829376 -7.314213276 -6.598470688 8.643713951 0.056779161 -0.049893674 0.003812397 0.997132003
1403638562727829504 -7.286360264 -6.606477737 8.648891449 0.057486333 -0.038986295 0.012136953 0.997510910
1403638562777829376 -7.266772270 -6.618177891 8.657857895 0.056825604 -0.027437417 0.020727511 0.997791767
1403638562827829504 -7.232038021 -6.617089272 8.670117378 0.057682797 -0.015358852 0.027488086 0.997838259
1403638562877829376 -7.226353645 -6.624146461 8.678577423 0.057299953 -0.001684250 0.034136388 0.997771800
1403638562927829504 -7.197286606 -6.625878334 8.691335678 0.057107791 0.011090187 0.039188076 0.997536957
1403638562977829376 -7.169519901 -6.624629974 8.684882164 0.056950964 0.023127995 0.044842660 0.997101188
1403638563027829504 -7.162145138 -6.611314774 8.680816650 0.058014154 0.035103831 0.052227668 0.996330440
1403638563077829376 -7.142557621 -6.625982285 8.673061371 0.056747455 0.045287095 0.060338482 0.995534062
1403638563127829504 -7.045736313 -6.621441841 8.692738533 0.056147546 0.051175285 0.068507373 0.994753897
1403638563177829376 -7.009057522 -6.615027428 8.692209244 0.056065328 0.062233169 0.070079036 0.994018435
1403638563227829504 -6.971284866 -6.615504265 8.694915771 0.057546005 0.070843577 0.074285321 0.993051529
1403638563277829376 -6.941966057 -6.607791901 8.699798584 0.059413534 0.079850912 0.075293317 0.992181838
1403638563327829504 -6.911296368 -6.600293159 8.701507568 0.064143121 0.086372696 0.077540524 0.991167426
1403638563377829376 -6.865641594 -6.589990139 8.701796532 0.070984013 0.090836093 0.079398312 0.990154505
1403638563427829504 -6.826768875 -6.576789856 8.705976486 0.077438034 0.094013587 0.081646770 0.989190876
1403638563477829376 -6.792919159 -6.566092491 8.695355415 0.080071829 0.096112624 0.084052719 0.988577724
1403638563527829504 -6.753773212 -6.556967735 8.695785522 0.079869874 0.098885499 0.081983879 0.988494396
1403638563577829376 -6.703775406 -6.534255981 8.693713188 0.078616418 0.100060023 0.080451891 0.988602519
1403638563627829504 -6.664606094 -6.520639896 8.684250832 0.075561441 0.101058193 0.079483695 0.988817513
1403638563677829376 -6.631216526 -6.512569904 8.667225838 0.072180770 0.100810833 0.080693193 0.988997340
1403638563727829504 -6.577690125 -6.494400978 8.653551102 0.070580624 0.099336639 0.081713878 0.989178181
1403638563777829376 -6.533812523 -6.479664326 8.639024734 0.068876423 0.098073982 0.082896508 0.989325881
1403638563827829504 -6.488997459 -6.468370438 8.620822906 0.068504147 0.096647389 0.083821110 0.989414215
1403638563877829376 -6.447720528 -6.459656239 8.598263741 0.069551565 0.095793597 0.083731703 0.989431739
1403638563927829504 -6.398691177 -6.451319695 8.574788094 0.069688559 0.093876414 0.084652685 0.989527464
1403638563977829376 -6.371481419 -6.455132008 8.541149139 0.070845380 0.093278214 0.084733374 0.989494979
1403638564027829504 -6.320561886 -6.446933746 8.515238762 0.069703840 0.090998180 0.085592054 0.989714444
1403638564077829376 -6.244864941 -6.420065880 8.491913795 0.070709631 0.087342396 0.085187122 0.990007401
1403638564127829504 -6.194597244 -6.406744480 8.464485168 0.071100667 0.085637741 0.084285736 0.990205407
1403638564177829376 -6.144943237 -6.393559933 8.433265686 0.071002789 0.084041134 0.082397237 0.990508139
1403638564227829504 -6.088282108 -6.373915195 8.403738976 0.072654746 0.082806379 0.079812102 0.990704000
1403638564277829376 -6.031668663 -6.357205391 8.367505074 0.074006811 0.081982359 0.077308215 0.990871012
1403638564327829504 -5.979520321 -6.342496872 8.329193115 0.074359901 0.081542999 0.073713407 0.991154730
1403638564377829376 -5.930493832 -6.327533722 8.292226791 0.076309159 0.080162413 0.073212110 0.991156340
1403638564427829504 -5.866492748 -6.313472748 8.255740166 0.077704474 0.079616301 0.070483945 0.991289675
1403638564477829376 -5.807417870 -6.297763824 8.214116096 0.078617327 0.078573175 0.069127060 0.991396487
1403638564527829504 -5.753461838 -6.286794662 8.160337448 0.077797882 0.077785484 0.069248095 0.991514802
1403638564577829376 -5.693163395 -6.272820950 8.114937782 0.075561188 0.076431461 0.070626721 0.991695821
1403638564627829504 -5.634810448 -6.258594513 8.076315880 0.074216269 0.075522788 0.072596952 0.991724730
1403638564677829376 -5.573503494 -6.237411499 8.022871971 0.073068276 0.073960416 0.075736232 0.991692960
1403638564727829504 -5.510030270 -6.218207359 7.975265980 0.072468556 0.073340654 0.077743828 0.991627634
1403638564777829376 -5.442021370 -6.198515892 7.923119068 0.071946211 0.072347507 0.080290616 0.991535664
1403638564827829504 -5.380792618 -6.178514481 7.865489960 0.071462005 0.072549097 0.082218103 0.991397977
1403638564877829376 -5.312616825 -6.151216507 7.819312096 0.072247460 0.072432369 0.084094472 0.991192222
1403638564927829504 -5.248948097 -6.117041111 7.767779827 0.073132344 0.072413847 0.085423142 0.991015017
1403638564977829376 -5.178604126 -6.083807468 7.722649097 0.072914965 0.072272055 0.086493209 0.990948558
1403638565027829504 -5.110674858 -6.049826622 7.665827751 0.072095700 0.072039582 0.087540112 0.990933478
1403638565077829376 -5.038984299 -6.005074978 7.622039318 0.071639396 0.071517073 0.088755652 0.990896344
1403638565127829504 -4.969701767 -5.955551624 7.582945824 0.070717834 0.071796067 0.088744260 0.990943372
1403638565177829376 -4.902368069 -5.907488346 7.520989895 0.069739342 0.071782775 0.089290500 0.990964592
1403638565227829504 -4.834533691 -5.856631279 7.470925331 0.068648592 0.072679125 0.088899598 0.991010606
1403638565277829376 -4.757829666 -5.804772854 7.412888527 0.067273565 0.073287383 0.088387750 0.991105855
1403638565327829504 -4.689680576 -5.758078575 7.366503239 0.065900147 0.074394584 0.087694161 0.991177261
1403638565377829376 -4.623344898 -5.702373505 7.285717010 0.063867316 0.075909995 0.087067269 0.991250694
1403638565427829504 -4.555251122 -5.652853012 7.238553047 0.062948361 0.077207804 0.086365335 0.991270661
1403638565477829376 -4.478384495 -5.596231461 7.170800686 0.063896053 0.079760954 0.084989011 0.991126835
1403638565527829504 -4.378391266 -5.522179127 7.129935741 0.066936485 0.080141000 0.081080228 0.991222918
1403638565577829376 -4.298062325 -5.467809677 7.073552132 0.068686344 0.082650997 0.078326449 0.991118550
1403638565627829504 -4.228938103 -5.420607090 7.049610615 0.069137931 0.087298736 0.073139995 0.991084993
1403638565677829376 -4.129373074 -5.349302292 6.971468449 0.069619216 0.089269273 0.065005191 0.991442621
1403638565727829504 -4.063323975 -5.312151909 6.890635967 0.066582754 0.093534596 0.060041398 0.991571009
1403638565777829376 -3.975082159 -5.245264053 6.837862968 0.064593330 0.095740438 0.056831449 0.991681218
1403638565827829504 -3.885018826 -5.177221298 6.821076393 0.064775154 0.096202835 0.054822199 0.991737723
1403638565877829376 -3.801120758 -5.154233932 6.721926689 0.059929211 0.098303251 0.051235557 0.992028177
1403638565927829504 -3.712301970 -5.102401257 6.644895554 0.057402197 0.098652467 0.050903216 0.992160082
1403638565977829376 -3.624843121 -5.059820175 6.578372478 0.056496155 0.099184819 0.049167793 0.992246449
1403638566027829504 -3.549046755 -5.018014908 6.518082619 0.054262713 0.099254742 0.050390333 0.992302835
1403638566077829376 -3.493031740 -4.966009617 6.441419125 0.053952977 0.102549098 0.050052647 0.992001772
1403638566127829504 -3.407758713 -4.888193130 6.388469696 0.055683311 0.101180598 0.049744893 0.992062151
1403638566177829376 -3.349388361 -4.874599457 6.284382820 0.052387893 0.102070749 0.051661465 0.992052495
1403638566227829504 -3.288453579 -4.801776886 6.275878906 0.055302810 0.102105878 0.050054114 0.991973102
1403638566277829376 -3.224849224 -4.760594845 6.170714378 0.052991811 0.103140697 0.050797038 0.991954386
1403638566327829504 -3.190701485 -4.704481125 6.124828815 0.052020926 0.104806140 0.052018758 0.991767883
1403638566377829376 -3.129927635 -4.625776768 6.054046631 0.052078053 0.105328381 0.050333995 0.991796494
1403638566427829504 -3.126651287 -4.577798367 6.036261559 0.052875232 0.107768252 0.050654009 0.991475821
1403638566477829376 -3.043240547 -4.529044151 5.980018616 0.051778212 0.105064780 0.050619386 0.991825640
1403638566527829504 -2.908358574 -4.434381485 5.814771652 0.050720423 0.101822898 0.051029697 0.992197335
1403638566577829376 -2.818351746 -4.338248730 5.737637043 0.046837252 0.097983114 0.054219317 0.992605627
1403638566627829504 -2.711624146 -4.251296043 5.562081814 0.038486637 0.095842615 0.055917177 0.993079185
1403638566677829376 -2.687641382 -4.188631058 5.567714691 0.030911099 0.098148853 0.050558411 0.993405819
1403638566727829504 -2.607501030 -4.102472782 5.552864552 0.020865075 0.093148187 0.055051997 0.993910134
1403638566777829376 -2.513568163 -4.008044243 5.412283897 0.009835635 0.091457181 0.056518771 0.994155169
1403638566827829504 -2.443315983 -3.928966045 5.336926937 0.001368484 0.089954466 0.055771083 0.994382143
1403638566877829376 -2.378130198 -3.835877419 5.283137798 -0.003786014 0.088673413 0.056018099 0.994477093
1403638566927829504 -2.401394606 -3.819617748 5.504994392 -0.002998659 0.092748970 0.046560697 0.994595766
1403638566977829376 -2.340994358 -3.751440048 5.462371826 -0.005907582 0.091904178 0.046311427 0.994672775
1403638567027829504 -2.286807537 -3.676615238 5.425980568 -0.002078435 0.092316054 0.045866732 0.994670630
1403638567077829376 -2.229001045 -3.630122185 5.381089211 0.007541947 0.092345543 0.044742320 0.994692683
1403638567127829504 -2.160068035 -3.550157070 5.345562458 0.019843094 0.092683040 0.041496795 0.994632661
1403638567177829376 -2.101227760 -3.480201483 5.301019192 0.031534463 0.093604408 0.040129326 0.994300425
1403638567227829504 -2.050077438 -3.416548014 5.274337769 0.040205326 0.095060498 0.037275508 0.993960559
1403638567277829376 -1.978337288 -3.362469912 5.235448360 0.044914383 0.094961025 0.037001994 0.993778586
1403638567327829504 -1.918442011 -3.283097267 5.187193394 0.047407638 0.096479096 0.034778379 0.993596911
1403638567377829376 -1.872884750 -3.212391853 5.133163452 0.047420483 0.098079234 0.034296751 0.993456304
1403638567427829504 -1.820563793 -3.157324791 5.095042229 0.047025472 0.098935582 0.035143878 0.993360579
1403638567477829376 -1.828266978 -3.102628469 5.095198631 0.045123126 0.103461206 0.034763779 0.993001103
1403638567527829504 -1.761138082 -3.049314022 5.073144436 0.042976510 0.103418805 0.036676828 0.993031919
1403638567577829376 -1.659861803 -2.976167440 5.021912098 0.038251102 0.101781331 0.037456665 0.993365228
1403638567627829504 -1.623377800 -2.919191122 4.978317261 0.034716014 0.103248067 0.034476910 0.993451536
1403638567677829376 -1.643618345 -2.833689690 4.932089806 0.034541585 0.108465731 0.034285381 0.992908120
1403638567727829504 -1.554335117 -2.754612684 4.904504776 0.033642206 0.108539678 0.032262687 0.992998719
1403638567777829376 -1.495828867 -2.717022657 4.862025261 0.028568052 0.108334139 0.033743966 0.993130863
1403638567827829504 -1.447470188 -2.627655268 4.807947159 0.026892867 0.109430484 0.031972047 0.993116081
1403638567877829376 -1.353471518 -2.551820993 4.768771172 0.025534809 0.107164830 0.037064008 0.993221998
1403638567927829504 -1.314184427 -2.514487505 4.739069939 0.023711184 0.107692815 0.037379131 0.993198276
1403638567977829376 -1.269421577 -2.465611935 4.695919991 0.023292573 0.108077951 0.037628401 0.993156910
1403638568027829504 -1.244748831 -2.431350470 4.652403355 0.022710441 0.109704986 0.038136389 0.992972612
1403638568077829376 -1.200773001 -2.390963554 4.625512123 0.023317577 0.111346215 0.035368491 0.992878318
1403638568127829504 -1.146496773 -2.352260590 4.581035137 0.024242623 0.110247329 0.035692763 0.992967188
1403638568177829376 -1.108466864 -2.304698229 4.553835869 0.025856765 0.111506589 0.033592723 0.992859125
1403638568227829504 -1.075202227 -2.256950140 4.525281906 0.027643165 0.112912789 0.031931296 0.992706895
1403638568277829376 -1.067927957 -2.203452826 4.475815773 0.028879302 0.116283387 0.031215876 0.992305279
1403638568327829504 -1.025404215 -2.151686430 4.473755836 0.030569598 0.117364682 0.029799594 0.992170870
1403638568377829376 -0.951160133 -2.196291208 4.427854538 0.022567756 0.113227293 0.033663899 0.992742181
1403638568427829504 -0.883666515 -2.116419315 4.375480175 0.024672650 0.111906052 0.032405879 0.992883742
1403638568477829376 -0.865302503 -2.102962971 4.349014759 0.022665847 0.112945713 0.032162394 0.992821753
1403638568527829504 -0.829147339 -2.083774090 4.316998482 0.020762930 0.112968370 0.033342469 0.992821932
1403638568577829376 -0.794348955 -2.032552242 4.303006172 0.020614063 0.113614202 0.031983681 0.992796063
1403638568627829504 -0.767648995 -2.016114235 4.268120766 0.017596804 0.113632478 0.032305777 0.992841542
1403638568677829376 -0.740609467 -2.031799793 4.251900673 0.013949100 0.111261033 0.030171938 0.993235171
1403638568727829504 -0.723759472 -1.992495418 4.233506203 0.013869151 0.112342052 0.029418526 0.993137181
1403638568777829376 -0.686466694 -1.971433759 4.208379269 0.011658803 0.111191735 0.030694377 0.993256390
1403638568827829504 -0.659589350 -1.948863268 4.190773010 0.012998704 0.110696644 0.031678192 0.993264198
1403638568877829376 -0.640962422 -1.928184628 4.167035580 0.012400234 0.110972464 0.033177339 0.993192136
1403638568927829504 -0.615961075 -1.912408113 4.150052071 0.012154312 0.111825690 0.031181959 0.993164122
1403638568977829376 -0.594053864 -1.889406204 4.129905701 0.012799608 0.111819677 0.030526578 0.993177056
1403638569027829504 -0.559914708 -1.861036062 4.105124474 0.014715563 0.110960886 0.030852588 0.993236780
1403638569077829376 -0.546707928 -1.846123934 4.087774277 0.013945836 0.112251811 0.029250711 0.993151307
1403638569127829504 -0.519915640 -1.829028368 4.070482254 0.014611297 0.111822851 0.029191883 0.993191838
1403638569177829376 -0.502703905 -1.817243576 4.053025246 0.012748366 0.112312727 0.028707618 0.993176341
1403638569227829504 -0.485897183 -1.809476614 4.036438465 0.011290998 0.113045171 0.027169157 0.993154168
1403638569277829376 -0.465034366 -1.804878592 4.021841049 0.009313688 0.113203987 0.027048511 0.993159831
1403638569327829504 -0.453077674 -1.800051570 4.009140491 0.008637197 0.113980725 0.026723316 0.993085921
1403638569377829376 -0.438152075 -1.775638461 3.999620676 0.009977025 0.114241228 0.026119795 0.993059516
1403638569427829504 -0.421172321 -1.763241410 3.990252733 0.011285892 0.114415340 0.025748467 0.993035138
1403638569477829376 -0.415804327 -1.756623268 3.982707024 0.011812751 0.114914730 0.025556434 0.992976308
1403638569527829504 -0.403283060 -1.743345261 3.976183891 0.012921412 0.114870355 0.025355173 0.992972791
1403638569577829376 -0.386468112 -1.726793051 3.971426964 0.014340276 0.114711814 0.024863176 0.992984116
1403638569627829504 -0.379582882 -1.716670036 3.968234539 0.015607591 0.114477195 0.026031652 0.992962062
1403638569677829376 -0.368751645 -1.709873557 3.964054346 0.016218752 0.114411071 0.026172312 0.992956221
1403638569727829504 -0.362712026 -1.698487997 3.960425854 0.017557831 0.114901498 0.025292367 0.992899656
1403638569777829376 -0.360238075 -1.700396299 3.955175161 0.017542930 0.115247890 0.025212612 0.992861807
1403638569827829504 -0.360448301 -1.695104599 3.952604294 0.018442759 0.115316898 0.024964077 0.992843747
1403638569877829376 -0.348573446 -1.694217443 3.950755358 0.019961733 0.115278631 0.023636676 0.992851317
1403638569927829504 -0.352148235 -1.692103386 3.948302507 0.021688361 0.115758255 0.023499120 0.992762506
1403638569977829376 -0.354870379 -1.693222523 3.945826530 0.023018885 0.115437731 0.024348194 0.992749453
1403638570027829504 -0.359465599 -1.698365808 3.944819450 0.023843400 0.115211025 0.025466785 0.992728233
1403638570077829376 -0.361066520 -1.703114390 3.945092916 0.023593675 0.114511855 0.026927788 0.992776573
1403638570127829504 -0.362670481 -1.692631721 3.947965860 0.024426866 0.113428481 0.029418238 0.992810071
1403638570177829376 -0.365862608 -1.688770294 3.948022127 0.024749778 0.111893274 0.031963561 0.992897630
1403638570227829504 -0.370385766 -1.686537743 3.949925423 0.025890928 0.110081784 0.035548586 0.992949128
1403638570277829376 -0.379495382 -1.685443997 3.956559658 0.026007313 0.108327627 0.039951641 0.992971599
1403638570327829504 -0.379308164 -1.672038078 3.960442066 0.027477408 0.106086023 0.045417212 0.992939055
1403638570377829376 -0.384737730 -1.669481635 3.966900110 0.027266527 0.106520087 0.049664408 0.992695034
1403638570427829504 -0.391710162 -1.659978867 3.972752094 0.027750833 0.108578853 0.056069590 0.992117286
1403638570477829376 -0.393267751 -1.651957273 3.979562521 0.027932320 0.111269169 0.065079175 0.991263628
1403638570527829504 -0.407942772 -1.643141866 3.988916159 0.029162191 0.115756884 0.077441238 0.989824593
1403638570577829376 -0.404130459 -1.630610943 3.994326115 0.030998649 0.120606735 0.091266207 0.988009870
1403638570627829504 -0.405721903 -1.624198675 4.006451607 0.032624219 0.128203884 0.104353115 0.985702693
1403638570677829376 -0.399857283 -1.613813400 4.012828350 0.035758588 0.137258723 0.114859328 0.983203292
1403638570727829504 -0.398607612 -1.600192189 4.025012493 0.041632876 0.148114845 0.123338968 0.980365336
1403638570777829376 -0.388708472 -1.591192007 4.028167248 0.048843466 0.158783868 0.133039102 0.977088809
1403638570827829504 -0.380649686 -1.555352092 4.037686825 0.058363784 0.170824021 0.139524549 0.973625064
1403638570877829376 -0.370219946 -1.541066051 4.044639587 0.064187780 0.182990626 0.145331234 0.970192373
1403638570927829504 -0.357536554 -1.519682169 4.050188541 0.068029419 0.195548862 0.150254890 0.966724455
1403638570977829376 -0.337335110 -1.498835921 4.048721790 0.070895121 0.207420856 0.154285088 0.963403642
1403638571027829504 -0.319921017 -1.472399354 4.045704365 0.072195485 0.219052970 0.159285113 0.959912419
1403638571077829376 -0.304125071 -1.463084102 4.043153763 0.067060940 0.232075021 0.160652295 0.956992626
1403638571127829504 -0.269857526 -1.425463200 4.033785343 0.062327985 0.243379697 0.161365241 0.954380870
1403638571177829376 -0.261624217 -1.393464804 4.030685425 0.057165638 0.256403089 0.159293637 0.951638103
1403638571227829504 -0.221103311 -1.382728696 4.011573792 0.050927840 0.265654236 0.157251045 0.949792802
1403638571277829376 -0.200669527 -1.349896431 4.001422882 0.048374947 0.275810003 0.154148474 0.947537303
1403638571327829504 -0.172288179 -1.336285233 3.980835199 0.044647586 0.283949256 0.151045367 0.945814312
1403638571377829376 -0.128245234 -1.309387326 3.951506615 0.044430692 0.287723035 0.151702777 0.944577992
1403638571427829504 -0.097567916 -1.279289484 3.934963703 0.046161324 0.291968703 0.151978284 0.943146884
1403638571477829376 -0.069438100 -1.274509549 3.912122250 0.046475869 0.295533270 0.152667552 0.941909075
1403638571527829504 -0.041019678 -1.243412614 3.888222456 0.049235184 0.299128503 0.151254073 0.940861464
1403638571577829376 -0.017738819 -1.240126491 3.865590572 0.047615539 0.304517806 0.151980251 0.939097285
1403638571627829504 0.041216373 -1.224749446 3.819616079 0.045536354 0.306734711 0.154177904 0.938120186
1403638571677829376 0.057826281 -1.214807868 3.798050404 0.042070586 0.313758045 0.156817466 0.935518146
1403638571727829504 0.095253944 -1.167216301 3.778056145 0.041362260 0.319573373 0.159723386 0.933086514
1403638571777829376 0.130357623 -1.146292567 3.753116131 0.037993144 0.326870382 0.163641945 0.930018067
1403638571827829504 0.163042307 -1.126629710 3.728591442 0.035181299 0.334782034 0.168102100 0.926512301
1403638571877829376 0.187745690 -1.109620333 3.712947130 0.033409506 0.344152570 0.174234256 0.922000647
1403638571927829504 0.232281923 -1.090402722 3.674714565 0.032399338 0.351632684 0.180281982 0.918043137
1403638571977829376 0.247075200 -1.061289310 3.659064531 0.033464130 0.362418443 0.185689673 0.912716985
1403638572027829504 0.291531086 -1.035054803 3.629471779 0.033687148 0.370786041 0.189992338 0.908452392
1403638572077829376 0.326732755 -1.026711822 3.579367399 0.033349447 0.379692316 0.196986660 0.903281689
1403638572127829504 0.372345448 -1.018897176 3.543488503 0.032355286 0.389693290 0.200733706 0.898219466
1403638572177829376 0.403916001 -0.997324526 3.521856785 0.031946044 0.402155787 0.200128704 0.892859817
1403638572227829504 0.446989655 -0.978420019 3.479405403 0.029540084 0.412344277 0.202443525 0.887759089
1403638572277829376 0.479864001 -0.982480049 3.452050924 0.024404190 0.423746943 0.206080019 0.881688118
1403638572327829504 0.526811361 -0.956289113 3.403725147 0.021806635 0.432845712 0.209749237 0.876455545
1403638572377829376 0.565090656 -0.945995808 3.374635220 0.017951433 0.444652081 0.213859513 0.869612753
1403638572427829504 0.605283260 -0.929515600 3.334234238 0.014430958 0.454338044 0.215906173 0.864148855
1403638572477829376 0.649534941 -0.908594370 3.296848297 0.011236596 0.463280857 0.216674611 0.859241903
1403638572527829504 0.699658751 -0.889816165 3.265723705 0.008353363 0.470429629 0.217814207 0.855092466
1403638572577829376 0.738961458 -0.873090863 3.235118389 0.007389828 0.478281945 0.217631876 0.850780904
1403638572627829504 0.797767639 -0.848632574 3.185888767 0.005867192 0.480931610 0.218696833 0.849024177
1403638572677829376 0.838689864 -0.831058323 3.146291018 0.004398080 0.484792382 0.219061479 0.846740246
1403638572727829504 0.886194348 -0.814278722 3.110035419 0.001526517 0.488801599 0.216774344 0.845032275
1403638572777829376 0.927208781 -0.823413372 3.080424786 -0.003652657 0.493183017 0.214554504 0.843044162
1403638572827829504 0.989443958 -0.786056280 3.034286022 -0.005087871 0.493197799 0.212836266 0.843463540
1403638572877829376 1.024461269 -0.803783417 3.009270668 -0.009583795 0.496712893 0.211967915 0.841578305
1403638572927829504 1.091508627 -0.766100407 2.949697018 -0.008454808 0.493940979 0.212270319 0.843144178
1403638572977829376 1.139110804 -0.760360420 2.913770199 -0.011099832 0.494946122 0.210919350 0.842863083
1403638573027829504 1.189335108 -0.753914118 2.881426811 -0.012824695 0.495067686 0.210893556 0.842773676
1403638573077829376 1.250145078 -0.749943495 2.846896648 -0.014655803 0.493914723 0.210539818 0.843508422
1403638573127829504 1.309078336 -0.726652265 2.804727793 -0.015010623 0.492230296 0.210840091 0.844411314
1403638573177829376 1.356133699 -0.729732633 2.784529686 -0.016285097 0.493010461 0.210228726 0.844084918
1403638573227829504 1.423161030 -0.707098007 2.741106510 -0.015058538 0.490433455 0.210484520 0.845543921
1403638573277829376 1.473727584 -0.695694745 2.714091301 -0.015455646 0.490221918 0.210575104 0.845636845
1403638573327829504 1.529859185 -0.687524259 2.676799536 -0.014920303 0.488847703 0.209567845 0.846691608
1403638573377829376 1.593251944 -0.679767132 2.651385307 -0.016388834 0.488860309 0.210038632 0.846540511
1403638573427829504 1.661810160 -0.668069780 2.625084162 -0.017707672 0.489825726 0.209385768 0.846117496
1403638573477829376 1.712919474 -0.665247321 2.587277889 -0.017984975 0.491085142 0.208371997 0.845631719
1403638573527829504 1.763984680 -0.670338929 2.551006794 -0.019132610 0.492383182 0.207837328 0.844983101
1403638573577829376 1.825657725 -0.673032343 2.516940117 -0.019553903 0.492380112 0.207607195 0.845031798
1403638573627829504 1.907602072 -0.657066286 2.511981964 -0.019002145 0.493395507 0.207302511 0.844526768
1403638573677829376 1.967560768 -0.676253974 2.474505663 -0.022372682 0.495691925 0.206135944 0.843384206
1403638573727829504 2.032845974 -0.687338650 2.440646172 -0.022517836 0.498012364 0.206474915 0.841929197
1403638573777829376 2.146564007 -0.643338084 2.413238525 -0.017968530 0.499600619 0.206907019 0.840990961
1403638573827829504 2.175537586 -0.675607800 2.391615152 -0.016295295 0.508295536 0.203567997 0.836618304
1403638573877829376 2.239964008 -0.683638453 2.364189148 -0.011908742 0.516680062 0.201764062 0.831980228
1403638573927829504 2.331212997 -0.674947977 2.363846540 -0.006498284 0.525159776 0.202051014 0.826644063
1403638573977829376 2.391317606 -0.685495853 2.343766689 0.000628382 0.533727825 0.204774976 0.820488513
1403638574027829504 2.461162090 -0.700555980 2.322037935 0.008449714 0.541552007 0.211410031 0.813606739
1403638574077829376 2.522663116 -0.708955884 2.297882080 0.016909480 0.549729347 0.218123958 0.806184649
1403638574127829504 2.615694046 -0.712455988 2.292636395 0.025501953 0.558861315 0.225409165 0.797630489
1403638574177829376 2.676907539 -0.714768112 2.273092985 0.033463906 0.567888021 0.233034968 0.788719296
1403638574227829504 2.770178080 -0.696106255 2.274230003 0.040776804 0.577430844 0.240158588 0.779252648
1403638574277829376 2.829005003 -0.691551626 2.266852379 0.043560632 0.587859929 0.245396376 0.769612730
1403638574327829504 2.891981602 -0.682056129 2.255186319 0.044155996 0.598308802 0.249772340 0.760059595
1403638574377829376 2.950139523 -0.674666584 2.224313259 0.042319439 0.607584298 0.254413664 0.751215041
1403638574427829504 3.028848410 -0.669023454 2.207931757 0.039728329 0.617461383 0.258198798 0.741954505
1403638574477829376 3.100881815 -0.651740491 2.188891172 0.038162671 0.626695931 0.262744844 0.732639730
1403638574527829504 3.159228325 -0.646753609 2.176712036 0.036335282 0.635741353 0.265943080 0.723731279
1403638574577829376 3.227521420 -0.634520531 2.146244526 0.035994861 0.641991019 0.268544257 0.717241824
1403638574627829504 3.289556265 -0.621834993 2.117797852 0.035901483 0.648662806 0.268774927 0.711131275
1403638574677829376 3.350812435 -0.611246109 2.097288609 0.032317422 0.655138493 0.268007755 0.705635250
1403638574727829504 3.413779974 -0.600325346 2.077446938 0.028113278 0.660853624 0.264959872 0.701625586
1403638574777829376 3.459828854 -0.608530402 2.042982101 0.021320214 0.664542139 0.264070213 0.698710322
1403638574827829504 3.513923168 -0.605285525 2.014585495 0.016329000 0.666567981 0.264817625 0.696629047
1403638574877829376 3.567549229 -0.603469014 1.986466169 0.012408134 0.667243421 0.267445743 0.695057571
1403638574927829504 3.623785496 -0.596986890 1.961995959 0.008856099 0.667523503 0.269716322 0.693964720
1403638574977829376 3.677692890 -0.593011618 1.937103510 0.006099735 0.667636335 0.271361083 0.693244338
1403638575027829504 3.728777885 -0.586879730 1.910629272 0.006646506 0.666333556 0.275169909 0.692991316
1403638575077829376 3.781534195 -0.578129172 1.884478331 0.009085267 0.664186597 0.280072153 0.693060756
1403638575127829504 3.834791183 -0.569287300 1.857402921 0.011953332 0.662970245 0.282830268 0.693061709
1403638575177829376 3.891359568 -0.557529569 1.834341168 0.014704301 0.661539733 0.285447359 0.693302751
1403638575227829504 3.941900015 -0.546866059 1.808574915 0.017321331 0.660636425 0.286582410 0.693635345
1403638575277829376 3.992479563 -0.536975026 1.780521035 0.018580003 0.659369826 0.287776053 0.694313407
1403638575327829504 4.049311638 -0.522372365 1.758431911 0.018050728 0.658361256 0.288845152 0.694840372
1403638575377829376 4.099334240 -0.508681655 1.729855061 0.015485252 0.656775177 0.290144056 0.695861340
1403638575427829504 4.157267570 -0.487372518 1.703944206 0.012361497 0.655115724 0.291054815 0.697106659
1403638575477829376 4.208603859 -0.469209552 1.680196047 0.008951759 0.654524207 0.290133119 0.698097885
1403638575527829504 4.263493061 -0.452235341 1.649357796 0.007177472 0.652791202 0.290594697 0.699547589
1403638575577829376 4.321510315 -0.433610439 1.622476578 0.003120084 0.652296603 0.288935751 0.700725019
1403638575627829504 4.378070831 -0.413714409 1.588641644 -0.001411319 0.651832998 0.286371678 0.702212930
1403638575677829376 4.435460091 -0.397762537 1.559965134 -0.004959356 0.651964486 0.283192486 0.703363121
1403638575727829504 4.494221210 -0.386773348 1.528985500 -0.010259769 0.651394606 0.281651884 0.704451561
1403638575777829376 4.553310394 -0.374660373 1.499911070 -0.014596323 0.651290834 0.280445963 0.704951942
1403638575827829504 4.613012791 -0.365904093 1.465004086 -0.018267401 0.650256515 0.279960513 0.706013381
1403638575877829376 4.678158283 -0.358512998 1.433306217 -0.019801343 0.649863183 0.279242694 0.706618190
1403638575927829504 4.743400574 -0.354842186 1.399569035 -0.020211771 0.649288058 0.279346764 0.707093954
1403638575977829376 4.809334278 -0.351081967 1.367476940 -0.019342462 0.649157286 0.278658688 0.707509756
1403638576027829504 4.874236584 -0.352212429 1.333917856 -0.019386016 0.648837388 0.278301209 0.707942545
1403638576077829376 4.943512440 -0.351298690 1.302160025 -0.019573329 0.649212420 0.276882410 0.708149910
1403638576127829504 5.011242867 -0.353313088 1.270183802 -0.018850645 0.649569631 0.277098536 0.707757235
1403638576177829376 5.083615303 -0.363115788 1.234915376 -0.017122118 0.649864197 0.275956541 0.707976937
1403638576227829504 5.149646759 -0.368087769 1.209778666 -0.017919306 0.650979221 0.273967206 0.707705319
1403638576277829376 5.218383789 -0.370175838 1.177382469 -0.018544177 0.652007997 0.271641999 0.707638502
1403638576327829504 5.295496941 -0.370154500 1.144707203 -0.020109067 0.652860999 0.268826932 0.707884312
1403638576377829376 5.358275414 -0.372162700 1.125855684 -0.022272890 0.654000103 0.266696423 0.707573831
1403638576427829504 5.448541164 -0.371051788 1.089315653 -0.024674809 0.654408932 0.265195787 0.707680225
1403638576477829376 5.526800632 -0.370070338 1.064350247 -0.027252072 0.655425370 0.262555927 0.707629383
1403638576527829504 5.600366592 -0.366990209 1.038822651 -0.031854931 0.656307578 0.260037541 0.707549393
1403638576577829376 5.683889866 -0.363152027 1.020568728 -0.035620004 0.657387972 0.257719189 0.707215071
1403638576627829504 5.760824203 -0.364244223 1.001337767 -0.038247909 0.658109665 0.255963743 0.707044065
1403638576677829376 5.840551376 -0.362429619 0.983179450 -0.038878273 0.658613980 0.254535079 0.707055867
1403638576727829504 5.920292854 -0.359788179 0.967968941 -0.037034314 0.659468830 0.251995742 0.707267582
1403638576777829376 5.999646187 -0.357605219 0.955972135 -0.034612551 0.661010385 0.248554423 0.707168996
1403638576827829504 6.084039688 -0.353201628 0.943872035 -0.029923111 0.662030816 0.245846912 0.707374752
1403638576877829376 6.169153690 -0.352263689 0.935788989 -0.025984142 0.662639320 0.244852647 0.707305491
1403638576927829504 6.249974251 -0.348597050 0.930204928 -0.020153485 0.662831008 0.245346844 0.707144856
1403638576977829376 6.332029819 -0.344001770 0.925460994 -0.014456297 0.662463009 0.246753499 0.707139671
1403638577027829504 6.410648346 -0.341918945 0.924314976 -0.011014543 0.661806047 0.249563217 0.706830680
1403638577077829376 6.491965294 -0.338065147 0.921395898 -0.007246847 0.661063075 0.251741081 0.706802309
1403638577127829504 6.572529793 -0.338385820 0.920370221 -0.004386725 0.660722435 0.253005385 0.706692934
1403638577177829376 6.654754162 -0.339573383 0.921365976 -0.002457241 0.660293221 0.254352003 0.706620038
1403638577227829504 6.726403236 -0.346984386 0.915289342 -0.001797564 0.660025775 0.255642951 0.706406057
1403638577277829376 6.808869362 -0.345084667 0.916437328 -0.002762434 0.660478413 0.254413486 0.706423700
1403638577327829504 6.889676571 -0.352569818 0.911416411 -0.005908386 0.661225736 0.251151174 0.706872463
1403638577377829376 6.956910610 -0.363208532 0.913751662 -0.011496685 0.662847519 0.246294230 0.706993759
1403638577427829504 7.030183315 -0.376577854 0.911858618 -0.015134066 0.663439453 0.243890002 0.707203388
1403638577477829376 7.110789776 -0.385149002 0.918365717 -0.016936868 0.664668798 0.240853846 0.707048774
1403638577527829504 7.203709602 -0.382622242 0.935685813 -0.016025966 0.664266050 0.242252126 0.706970811
1403638577577829376 7.291147232 -0.395867586 0.929819345 -0.015270342 0.663373232 0.244446114 0.707070589
1403638577627829504 7.358892441 -0.414607048 0.927916825 -0.013647842 0.662823379 0.246728003 0.706826866
1403638577677829376 7.423677921 -0.432250023 0.933798313 -0.013597903 0.661741793 0.247475520 0.707579494
1403638577727829504 7.455889225 -0.439908504 0.939185202 -0.012769132 0.661287367 0.248696089 0.707591891
1403638577777829376 7.557405949 -0.451863050 0.957953095 -0.011456816 0.660296381 0.251348287 0.707602620
1403638577827829504 7.663330078 -0.454404593 0.970375419 -0.011698795 0.660022974 0.251663297 0.707741737
1403638577877829376 7.734713554 -0.458196402 0.984960556 -0.011821322 0.660117388 0.250565350 0.708041131
1403638577927829504 7.815421104 -0.457957983 1.000388384 -0.011188196 0.659492552 0.250852287 0.708531916
1403638577977829376 7.878933430 -0.467623472 1.015748739 -0.012248089 0.659952879 0.249084339 0.708709478
1403638578027829504 7.948679447 -0.475205898 1.021055698 -0.011047833 0.659368992 0.249345168 0.709180832
1403638578077829376 8.027848244 -0.482128382 1.049321890 -0.009403299 0.659228623 0.249980241 0.709111452
1403638578127829504 8.094455719 -0.498103380 1.071943283 -0.007425021 0.658764243 0.250802428 0.709276199
1403638578177829376 8.166193008 -0.516402960 1.081597805 -0.004133067 0.657247961 0.253077984 0.709901094
1403638578227829504 8.239809990 -0.527616978 1.097166657 0.002293424 0.655300260 0.258079290 0.709909379
1403638578277829376 8.345398903 -0.540387630 1.117470741 0.006785155 0.653568506 0.262721509 0.709774315
1403638578327829504 8.417139053 -0.552082062 1.129081011 0.010367448 0.652419627 0.265241474 0.709850788
1403638578377829376 8.487936020 -0.567547798 1.150677323 0.010804459 0.653218269 0.264894456 0.709239066
1403638578427829504 8.558568954 -0.583841324 1.161239505 0.010444655 0.652868271 0.265287161 0.709419966
1403638578477829376 8.624628067 -0.592607737 1.172071934 0.011285332 0.652792692 0.265354902 0.709451318
1403638578527829504 8.696816444 -0.603340864 1.191671729 0.010649844 0.653129101 0.265490562 0.709100664
1403638578577829376 8.765576363 -0.613956928 1.199378371 0.011207711 0.653030396 0.266127467 0.708944201
1403638578627829504 8.833550453 -0.620978117 1.223643422 0.011525680 0.654029608 0.264948040 0.708459556
1403638578677829376 8.903249741 -0.626211166 1.237027407 0.010414628 0.654768705 0.263123065 0.708474219
1403638578727829504 9.001375198 -0.629039288 1.256057620 0.008391952 0.655493140 0.261472702 0.708442211
1403638578777829376 9.069335938 -0.631723642 1.277861238 0.005594429 0.656857371 0.258171976 0.708416760
1403638578827829504 9.126112938 -0.643524885 1.292177320 0.001427599 0.657411993 0.255703241 0.708818257
1403638578877829376 9.192813873 -0.642085552 1.304091454 0.000466833 0.658658624 0.252683520 0.708745122
1403638578927829504 9.260707855 -0.642278433 1.318969131 -0.001000292 0.659071267 0.251351535 0.708834589
1403638578977829376 9.327610016 -0.654564857 1.335786939 -0.001960181 0.659460962 0.249243379 0.709214509
1403638579027829504 9.384514809 -0.648020506 1.356661558 -0.001872002 0.659427226 0.248599142 0.709472120
1403638579077829376 9.445106506 -0.671624422 1.371456742 -0.002335384 0.659239590 0.249001324 0.709504068
1403638579127829504 9.550632477 -0.662054062 1.396260142 -0.002274716 0.659587324 0.247212946 0.709806442
1403638579177829376 9.610645294 -0.669434786 1.414421916 -0.001801533 0.659517109 0.246923745 0.709973693
1403638579227829504 9.666953087 -0.688065529 1.425356030 -0.001766957 0.659132898 0.246860310 0.710352480
1403638579277829376 9.732131958 -0.715939760 1.447111011 0.000272187 0.658467829 0.248778045 0.710302413
1403638579327829504 9.804269791 -0.738655090 1.461504221 0.001612809 0.657729983 0.250107348 0.710517406
1403638579377829376 9.838033676 -0.770831108 1.474877954 0.005851548 0.656014025 0.255714387 0.710085511
1403638579427829504 9.915913582 -0.782648563 1.498010397 0.010350237 0.654933929 0.258713514 0.709944904
1403638579477829376 9.990133286 -0.775813341 1.510095119 0.015170157 0.653176069 0.261658102 0.710398376
1403638579527829504 10.043725967 -0.794031143 1.529939771 0.018073635 0.652056098 0.262941748 0.710885227
1403638579577829376 10.108571053 -0.816242218 1.551350594 0.022385383 0.651363194 0.260228842 0.712394416
1403638579627829504 10.170763016 -0.826825857 1.561639309 0.028036714 0.649579823 0.255278468 0.715606689
1403638579677829376 10.218307495 -0.837651730 1.600110888 0.030863592 0.647758245 0.248701334 0.719447255
1403638579727829504 10.295907021 -0.840980768 1.607342124 0.031473327 0.642981231 0.241140425 0.726247787
1403638579777829376 10.335229874 -0.840868711 1.622690201 0.031354990 0.636437535 0.234182790 0.734249651
1403638579827829504 10.402659416 -0.823089361 1.641785026 0.028198881 0.627459586 0.228924721 0.743702054
1403638579877829376 10.468951225 -0.825331450 1.660569310 0.023242909 0.616696894 0.223057956 0.754579306
1403638579927829504 10.510704994 -0.820402145 1.694231391 0.021035269 0.604692817 0.218699843 0.765555024
1403638579977829376 10.561606407 -0.831598282 1.717662573 0.020038771 0.590646386 0.214262590 0.777706146
1403638580027829504 10.613054276 -0.844695568 1.748990655 0.021965779 0.576732337 0.204017520 0.790742755
1403638580077829376 10.675067902 -0.831090808 1.769308567 0.027778763 0.561456084 0.192427665 0.804342628
1403638580127829504 10.671610832 -0.874891400 1.777574539 0.032806605 0.545398295 0.184186578 0.817031026
1403638580177829376 10.717539787 -0.894466162 1.819710255 0.036476459 0.528304279 0.175923854 0.829828203
1403638580227829504 10.758827209 -0.874589443 1.833929539 0.039486784 0.508430779 0.166969597 0.843836546
1403638580277829376 10.807312012 -0.862309515 1.894048452 0.040331595 0.490139633 0.159574464 0.855962873
1403638580327829504 10.835334778 -0.871615648 1.888745785 0.039967123 0.469046444 0.157205507 0.868150055
1403638580377829376 10.860893250 -0.846969366 1.895102978 0.040768757 0.449632376 0.157434538 0.878284156
1403638580427829504 10.876304626 -0.845063806 1.901881218 0.041498739 0.431839317 0.160137624 0.886650205
1403638580477829376 10.896547318 -0.812161684 1.960068226 0.041115291 0.420002282 0.158843905 0.892567277
1403638580527829504 10.951356888 -0.853119135 2.026311398 0.039976280 0.410284489 0.158479884 0.897191525
1403638580577829376 10.965580940 -0.827211738 1.987122059 0.039817303 0.398236662 0.158281624 0.902645588
1403638580627829504 10.985800743 -0.789130867 1.992341042 0.039034259 0.387465507 0.157110542 0.907558858
1403638580677829376 11.020995140 -0.775633097 2.019277096 0.035232466 0.377553105 0.154270306 0.912366748
1403638580727829504 11.035888672 -0.784921169 2.056152821 0.030411869 0.368975401 0.151784062 0.916457236
1403638580777829376 11.062711716 -0.775815666 2.054131508 0.026236452 0.361076802 0.148144960 0.920319676
1403638580827829504 11.044169426 -0.810483515 2.051610470 0.021985721 0.356237322 0.147245318 0.922458887
1403638580877829376 11.063638687 -0.799973190 2.060226917 0.018702103 0.351630956 0.143289939 0.924918354
1403638580927829504 11.132987022 -0.768352449 2.091267109 0.020237893 0.347428143 0.141313344 0.926776469
1403638580977829376 11.148036003 -0.779995024 2.094859123 0.020514855 0.344311953 0.143301696 0.927627623
1403638581027829504 11.163187027 -0.786724448 2.098373413 0.020189792 0.342624038 0.143205360 0.928274393
1403638581077829376 11.207301140 -0.771798134 2.131763935 0.019505784 0.342963994 0.140409797 0.928590477
1403638581127829504 11.228321075 -0.791212678 2.133965492 0.019157326 0.343173414 0.139714733 0.928625226
1403638581177829376 11.249941826 -0.825419307 2.144694328 0.018880045 0.344052494 0.139709622 0.928306341
1403638581227829504 11.287724495 -0.825147033 2.153261662 0.018515812 0.344821692 0.138611466 0.928192914
1403638581277829376 11.305452347 -0.843081892 2.175168991 0.017557884 0.347661406 0.136779428 0.927423656
1403638581327829504 11.366317749 -0.832913280 2.184017181 0.017931793 0.348062634 0.136271730 0.927340746
1403638581377829376 11.431306839 -0.809290648 2.209260464 0.020890597 0.349044174 0.135504767 0.927022219
1403638581427829504 11.409240723 -0.850247502 2.200800896 0.020347957 0.351717860 0.135206088 0.926066875
1403638581477829376 11.445886612 -0.843342483 2.218355656 0.022137025 0.353298336 0.134347707 0.925548971
1403638581527829504 11.454860687 -0.855145097 2.220075607 0.022401333 0.354722500 0.135220304 0.924870610
1403638581577829376 11.489753723 -0.911669254 2.237351894 0.021326648 0.356303275 0.135553613 0.924239337
1403638581627829504 11.508516312 -0.935465336 2.235499859 0.023266008 0.358163446 0.134816289 0.923581243
1403638581677829376 11.545907974 -0.940498710 2.253379345 0.027188467 0.360245615 0.132731646 0.922966003
1403638581727829504 11.538484573 -0.954723358 2.276315689 0.031087866 0.362799942 0.131929353 0.921956837
1403638581777829376 11.593158722 -0.971491158 2.275324345 0.031480078 0.363051414 0.131941766 0.921842754
1403638581827829504 11.592435837 -0.990084410 2.277627468 0.031605657 0.364388108 0.131221294 0.921413779
1403638581877829376 11.612703323 -0.986716390 2.277167320 0.035812467 0.365167975 0.130014569 0.921122193
1403638581927829504 11.631374359 -0.994239450 2.312916279 0.043084346 0.367039859 0.128432155 0.920288384
1403638581977829376 11.668163300 -1.015974045 2.307428360 0.046482783 0.367729485 0.125619397 0.920235932
1403638582027829504 11.671998978 -1.031003594 2.307986736 0.046537332 0.368005812 0.125520617 0.920136213
1403638582077829376 11.672002792 -1.004852057 2.346445560 0.043954555 0.369090289 0.126233757 0.919731140
1403638582127829504 11.669882774 -1.037647009 2.338024139 0.036628526 0.368384212 0.129742563 0.919846892
1403638582177829376 11.688420296 -1.041958928 2.350034237 0.031977899 0.366361737 0.133787721 0.920248508
1403638582227829504 11.710321426 -1.028113842 2.339107513 0.027923850 0.365744114 0.133529201 0.920663595
1403638582277829376 11.712267876 -1.028002858 2.355300903 0.028500017 0.365888864 0.133451238 0.920599759
1403638582327829504 11.715970993 -1.087917447 2.346841335 0.029013289 0.366950959 0.131777361 0.920402110
1403638582377829376 11.741108894 -1.104392052 2.337131023 0.031560939 0.366668731 0.129368037 0.920772433
1403638582427829504 11.729616165 -1.122217417 2.355595589 0.033169005 0.368168831 0.127826244 0.920332551
1403638582477829376 11.724561691 -1.132870793 2.363757133 0.034363143 0.368914187 0.126228198 0.920210838
1403638582527829504 11.746164322 -1.156514168 2.369851589 0.035563793 0.368525982 0.126494899 0.920284152
1403638582577829376 11.754819870 -1.181429625 2.376947880 0.035745542 0.369055718 0.125669658 0.920177817
1403638582627829504 11.767047882 -1.225471258 2.363745213 0.035608929 0.368342608 0.126506060 0.920354247
1403638582677829376 11.758153915 -1.222030759 2.369327068 0.034975145 0.368481159 0.126409054 0.920336425
1403638582727829504 11.764850616 -1.235201001 2.365007401 0.033832010 0.367870033 0.127756596 0.920437574
1403638582777829376 11.769731522 -1.246478558 2.368948936 0.034039903 0.367882490 0.128255233 0.920355558
1403638582827829504 11.771421432 -1.280488491 2.355226517 0.031623032 0.367668241 0.128168091 0.920539498
1403638582877829376 11.779088974 -1.342271090 2.340558052 0.029301193 0.367247969 0.129714534 0.920567453
1403638582927829504 11.773969650 -1.366770148 2.340404510 0.027805643 0.367425978 0.130522162 0.920428693
1403638582977829376 11.729867935 -1.406942725 2.346386909 0.025461266 0.368403822 0.132386416 0.919839203
1403638583027829504 11.735081673 -1.408730149 2.344582081 0.023983341 0.368210763 0.132744461 0.919904649
1403638583077829376 11.728662491 -1.416973829 2.353507519 0.022193229 0.368345678 0.134296909 0.919670224
1403638583127829504 11.730403900 -1.427791476 2.345108986 0.021250231 0.367993772 0.134346411 0.919826090
1403638583177829376 11.710769653 -1.461461067 2.346287251 0.019715913 0.368387759 0.135263935 0.919568062
1403638583227829504 11.722229004 -1.503045201 2.333665371 0.018017391 0.367210418 0.136814699 0.919844329
1403638583277829376 11.715888023 -1.467746615 2.357350826 0.020162338 0.367729425 0.136500925 0.919639111
1403638583327829504 11.700374603 -1.494690895 2.360352516 0.019268284 0.368479371 0.135285631 0.919537663
1403638583377829376 11.684980392 -1.545280218 2.343565464 0.018179798 0.367398113 0.136524007 0.919809341
1403638583427829504 11.674587250 -1.549200892 2.356547832 0.018120987 0.367548555 0.136412337 0.919767022
1403638583477829376 11.644382477 -1.545083523 2.362694263 0.018369175 0.367903650 0.137243450 0.919496477
1403638583527829504 11.656334877 -1.599336147 2.364526749 0.016198007 0.367521256 0.137210891 0.919695020
1403638583577829376 11.649385452 -1.608887553 2.380995750 0.016957803 0.367880493 0.137285650 0.919526517
1403638583627829504 11.663928986 -1.595660925 2.375028133 0.017957363 0.367212236 0.135160625 0.920089245
1403638583677829376 11.656524658 -1.640000820 2.370326042 0.016265448 0.367502511 0.134234354 0.920140445
1403638583727829504 11.660148621 -1.643218756 2.382754326 0.017520094 0.367206991 0.133592740 0.920328796
1403638583777829376 11.627946854 -1.681354046 2.383463860 0.017742885 0.367243439 0.134021834 0.920247555
1403638583827829504 11.623418808 -1.708170414 2.387935162 0.017153345 0.367419094 0.133023456 0.920333505
1403638583877829376 11.615940094 -1.727669477 2.401459217 0.018736461 0.367604345 0.133067816 0.920222223
1403638583927829504 11.604251862 -1.744262218 2.399782658 0.019191420 0.366952389 0.133136481 0.920463085
1403638583977829376 11.579732895 -1.758476496 2.439154625 0.019046949 0.368380845 0.132783785 0.919946313
1403638584027829504 11.572666168 -1.798035622 2.446070194 0.019221902 0.368608117 0.131955132 0.919970870
1403638584077829376 11.556824684 -1.840819597 2.456651688 0.022414375 0.370018601 0.128987461 0.919753253
1403638584127829504 11.549825668 -1.837847710 2.463331699 0.030253012 0.370440811 0.125777617 0.919803441
1403638584177829376 11.542705536 -1.829509974 2.478366375 0.039424088 0.371488601 0.122682564 0.919451416
1403638584227829504 11.517885208 -1.862535596 2.487822533 0.047098204 0.372969538 0.119480006 0.918912411
1403638584277829376 11.514987946 -1.827491164 2.505423069 0.055928651 0.372462064 0.118029810 0.918810606
1403638584327829504 11.485041618 -1.856851578 2.511865616 0.057857241 0.373704970 0.116788752 0.918344975
1403638584377829376 11.461602211 -1.869900823 2.530145645 0.058447730 0.373809844 0.115955926 0.918370426
1403638584427829504 11.442287445 -1.873235226 2.530791759 0.058417629 0.373426974 0.116199039 0.918497384
1403638584477829376 11.422177315 -1.867087126 2.562123775 0.059185736 0.374079466 0.115343995 0.918290436
1403638584527829504 11.388435364 -1.887376785 2.569668770 0.059303071 0.373716712 0.116690278 0.918260515
1403638584577829376 11.366014481 -1.881065369 2.575644493 0.058594953 0.373801559 0.115291037 0.918448150
1403638584627829504 11.345152855 -1.914687395 2.563092709 0.056431469 0.372515827 0.116428919 0.918962300
1403638584677829376 11.303731918 -1.910292745 2.593060970 0.055243466 0.372651190 0.117636643 0.918825805
1403638584727829504 11.271347046 -1.913210869 2.605282784 0.052249640 0.372168303 0.119684450 0.918932199
1403638584777829376 11.260499001 -1.916411638 2.587015152 0.045157589 0.369168520 0.122558318 0.920138478
1403638584827829504 11.205274582 -1.917000055 2.599047661 0.039678615 0.368592590 0.124951050 0.920300126
1403638584877829376 11.158316612 -1.928239584 2.602889538 0.033621926 0.366827697 0.130535170 0.920471370
1403638584927829504 11.130455017 -1.927598476 2.615748882 0.030945439 0.366716266 0.132174060 0.920375764
1403638584977829376 11.094655037 -1.949088454 2.615405083 0.027443748 0.365893781 0.133466780 0.920627594
1403638585027829504 11.059709549 -1.955294132 2.603699684 0.025315328 0.364787668 0.134864986 0.920923769
1403638585077829376 11.011754990 -1.963239312 2.601081848 0.024848172 0.365392685 0.134530917 0.920745432
1403638585127829504 10.992074013 -1.955436468 2.601810932 0.025649181 0.364187211 0.136094689 0.920971215
1403638585177829376 10.944540024 -1.973247170 2.612525463 0.025464199 0.364065886 0.136945277 0.920898259
1403638585227829504 10.904529572 -1.984690428 2.630268574 0.025972988 0.365241289 0.136042804 0.920552313
1403638585277829376 10.875192642 -1.972509861 2.636752129 0.028474586 0.364991993 0.134959787 0.920736611
1403638585327829504 10.847473145 -1.966302156 2.640240192 0.031642351 0.364818215 0.134222984 0.920809746
1403638585377829376 10.801918030 -1.980973721 2.637455940 0.031357631 0.365003347 0.133692816 0.920823276
1403638585427829504 10.781473160 -1.961902261 2.648169518 0.032817513 0.364578217 0.134356722 0.920844197
1403638585477829376 10.728384018 -1.965063572 2.642891884 0.031793810 0.364376307 0.134190068 0.920984268
1403638585527829504 10.701141357 -1.973953605 2.657217503 0.030161971 0.364563853 0.134099334 0.920978189
1403638585577829376 10.646796227 -1.967372537 2.655248642 0.029412992 0.363910854 0.135055542 0.921120942
1403638585627829504 10.624820709 -1.982452035 2.672221184 0.026883723 0.364017516 0.134698331 0.921208382
1403638585677829376 10.579431534 -1.991458893 2.665128946 0.024188302 0.363641828 0.135286912 0.921345174
1403638585727829504 10.530927658 -2.009251356 2.667551994 0.020008057 0.362798303 0.137061864 0.921515644
1403638585777829376 10.489356995 -2.031816006 2.656010389 0.016300468 0.361378908 0.140498877 0.921628773
1403638585827829504 10.447828293 -2.051972151 2.673916578 0.012230751 0.361337781 0.142345458 0.921424568
1403638585877829376 10.385854721 -2.049602032 2.663121700 0.009985451 0.360171109 0.144204825 0.921619236
1403638585927829504 10.342494965 -2.046246767 2.685696840 0.010298901 0.360030562 0.146160409 0.921362579
1403638585977829376 10.318184853 -2.082143784 2.660340071 0.009757610 0.359734684 0.146416873 0.921443343
1403638586027829504 10.312976837 -2.081944704 2.658733606 0.013947112 0.359636813 0.144932285 0.921662331
1403638586077829376 10.266504288 -2.106576443 2.674998283 0.017009966 0.361511528 0.144050166 0.921015561
1403638586127829504 10.191457748 -2.144525528 2.714340210 0.019119505 0.364225179 0.143672138 0.919963479
1403638586177829376 10.178653717 -2.127161503 2.698401451 0.022368401 0.363424122 0.142543852 0.920382440
1403638586227829504 10.138778687 -2.174170017 2.705509186 0.022668988 0.364520222 0.141553268 0.920094430
1403638586277829376 10.136102676 -2.161007881 2.696970940 0.025773427 0.364221245 0.139422312 0.920456409
1403638586327829504 10.099655151 -2.169991255 2.721548319 0.029096307 0.365870893 0.137373745 0.920011103
1403638586377829376 10.045601845 -2.181166172 2.743290901 0.030625613 0.368537724 0.132744491 0.919576466
1403638586427829504 10.025928497 -2.182244301 2.732447386 0.032874443 0.369749784 0.128410026 0.919627786
1403638586477829376 9.997505188 -2.175996304 2.726137877 0.032717358 0.371082783 0.123383693 0.919784546
1403638586527829504 9.945773125 -2.189177275 2.725208044 0.033359200 0.372412533 0.120877236 0.919556856
1403638586577829376 9.921594620 -2.216616631 2.733912468 0.033246078 0.371773094 0.122389778 0.919619620
1403638586627829504 9.899478912 -2.219236851 2.718695879 0.031930741 0.369952917 0.124475904 0.920120120
1403638586677829376 9.846104622 -2.218153477 2.733962059 0.031445876 0.370181352 0.125238836 0.919941366
1403638586727829504 9.811596870 -2.207071304 2.766037464 0.033530984 0.369365126 0.128296211 0.919774532
1403638586777829376 9.772007942 -2.220424175 2.793475866 0.033826847 0.368796349 0.130143076 0.919732451
1403638586827829504 9.734073639 -2.203050375 2.778877974 0.035572316 0.367231220 0.131637886 0.920080066
1403638586877829376 9.692888260 -2.230870485 2.799381971 0.035140008 0.367214024 0.132069290 0.920041680
1403638586927829504 9.651447296 -2.248743534 2.818178415 0.035045445 0.367583275 0.132110596 0.919891894
1403638586977829376 9.604561806 -2.216280460 2.821960688 0.035186540 0.367259979 0.131037980 0.920169055
1403638587027829504 9.569145203 -2.239965916 2.859207153 0.035382763 0.367536098 0.132634059 0.919822514
1403638587077829376 9.526294708 -2.232838154 2.864025831 0.035039611 0.367472798 0.132268116 0.919913650
1403638587127829504 9.467993736 -2.242739439 2.903116941 0.034436677 0.368344128 0.132570893 0.919544280
1403638587177829376 9.443429947 -2.225563765 2.906241417 0.033120342 0.367245644 0.132230103 0.920080900
1403638587227829504 9.399064064 -2.254148483 2.900494337 0.030026415 0.366528481 0.132727608 0.920401394
1403638587277829376 9.362203598 -2.235453606 2.910544634 0.030055190 0.366053283 0.133191422 0.920522511
1403638587327829504 9.315026283 -2.239601851 2.915317774 0.027785935 0.366121680 0.133220315 0.920562446
1403638587377829376 9.284074783 -2.270278215 2.899274826 0.025732549 0.364862293 0.133951679 0.921015918
1403638587427829504 9.219195366 -2.267073870 2.919021368 0.026932627 0.365008771 0.135446370 0.920704901
1403638587477829376 9.174101830 -2.263524532 2.938266754 0.027142605 0.365098387 0.136271819 0.920541406
1403638587527829504 9.140560150 -2.252721310 2.954219103 0.028727224 0.364903271 0.136412799 0.920549750
1403638587577829376 9.092137337 -2.285102367 2.950196028 0.026589660 0.364940315 0.137837023 0.920387149
1403638587627829504 9.049170494 -2.275084734 2.973055840 0.027978633 0.364798188 0.138488650 0.920304477
1403638587677829376 9.010257721 -2.272697687 2.961573362 0.027482836 0.364216566 0.138137445 0.920602560
1403638587727829504 8.946598053 -2.280646324 2.991599560 0.028005587 0.365071446 0.138264641 0.920229018
1403638587777829376 8.917057037 -2.270457983 2.992733955 0.028589092 0.364783406 0.138806835 0.920243680
1403638587827829504 8.867958069 -2.284283161 2.984621048 0.028113846 0.364428639 0.139351770 0.920316517
1403638587877829376 8.827720642 -2.268548489 3.018698215 0.029143482 0.364826322 0.139800206 0.920058846
1403638587927829504 8.779619217 -2.284710646 3.043021202 0.028794041 0.364997119 0.139953747 0.919978797
1403638587977829376 8.748775482 -2.243638754 3.014992237 0.029174620 0.364228845 0.139231369 0.920380831
1403638588027829504 8.692066193 -2.279031038 3.060631275 0.029016757 0.365179598 0.140166372 0.919866979
1403638588077829376 8.649637222 -2.256331682 3.056393147 0.029243100 0.365059584 0.138761848 0.920120358
1403638588127829504 8.595252991 -2.280060768 3.092631340 0.027533492 0.367459327 0.136233971 0.919595480
1403638588177829376 8.579078674 -2.224698782 3.073302269 0.027853064 0.367356569 0.131064504 0.920377910
1403638588227829504 8.530113220 -2.234874487 3.129232645 0.026262561 0.369579405 0.128940314 0.919834614
1403638588277829376 8.473523140 -2.232118607 3.140158653 0.025657123 0.370327711 0.127564281 0.919742584
1403638588327829504 8.437343597 -2.223661661 3.136673927 0.025696691 0.369488895 0.128127873 0.920000494
1403638588377829376 8.397374153 -2.209249020 3.167893648 0.026025750 0.369867206 0.126719192 0.920034289
1403638588427829504 8.338951111 -2.222878695 3.175070763 0.025148315 0.369608968 0.127645731 0.920034409
1403638588477829376 8.293621063 -2.211273670 3.182264805 0.025592290 0.369025499 0.128462091 0.920142770
1403638588527829504 8.245080948 -2.222023010 3.187200546 0.026086178 0.368635297 0.130308583 0.920025647
1403638588577829376 8.223534584 -2.213885784 3.206291914 0.027323714 0.367744118 0.130683333 0.920293152
1403638588627829504 8.163712502 -2.251395702 3.197343588 0.027583342 0.366911680 0.132825986 0.920310915
1403638588677829376 8.103697777 -2.246830940 3.238856316 0.028439349 0.367653310 0.133229807 0.919930458
1403638588727829504 8.076944351 -2.235874653 3.248037815 0.031782195 0.366434336 0.134665430 0.920098364
1403638588777829376 8.008843422 -2.246198177 3.253509283 0.031966921 0.367053926 0.134566203 0.919859469
1403638588827829504 7.966977119 -2.248328209 3.254940987 0.032357071 0.366464585 0.135506585 0.919942737
1403638588877829376 7.899019718 -2.290948629 3.245894670 0.031823989 0.366178155 0.137911886 0.919717968
1403638588927829504 7.860333443 -2.292425394 3.248100519 0.032143433 0.366135627 0.137680173 0.919758499
1403638588977829376 7.810403347 -2.302630424 3.262515783 0.031805743 0.366101831 0.137829214 0.919761360
1403638589027829504 7.767016411 -2.310839176 3.268312931 0.031193007 0.366046786 0.138616070 0.919686019
1403638589077829376 7.705680847 -2.309940100 3.281646252 0.031139703 0.366564959 0.138435453 0.919508576
1403638589127829504 7.662775040 -2.307372570 3.289414167 0.030670505 0.367023230 0.137208670 0.919525445
1403638589177829376 7.609251499 -2.300412655 3.302392244 0.031361189 0.367932975 0.136494786 0.919244766
1403638589227829504 7.565448761 -2.290496111 3.295771360 0.031676352 0.366523027 0.137643293 0.919625878
1403638589277829376 7.525416374 -2.287510872 3.303135633 0.032979738 0.366642952 0.137355670 0.919575274
1403638589327829504 7.472544670 -2.308324099 3.327475071 0.030693702 0.367715389 0.136282817 0.919385791
1403638589377829376 7.424173832 -2.296527624 3.335037708 0.032012340 0.367569506 0.135379136 0.919532657
1403638589427829504 7.369669914 -2.304257393 3.345099449 0.030696312 0.367282391 0.136741474 0.919490695
1403638589477829376 7.338455200 -2.280513763 3.346244574 0.031191446 0.366498172 0.136460200 0.919828653
1403638589527829504 7.278828621 -2.298110485 3.359979868 0.030199070 0.366568565 0.136738271 0.919792414
1403638589577829376 7.227989197 -2.302916050 3.354150295 0.030322887 0.366668969 0.137619287 0.919616938
1403638589627829504 7.184021950 -2.298239708 3.357536316 0.031049805 0.366744697 0.136514604 0.919727147
1403638589677829376 7.113425732 -2.308878899 3.360522985 0.029652754 0.366824716 0.137758479 0.919555843
1403638589727829504 7.083653927 -2.322245121 3.346724987 0.027388219 0.366144091 0.138555631 0.919777513
1403638589777829376 7.052275658 -2.314402342 3.327572346 0.026646463 0.365832955 0.137386769 0.920098424
1403638589827829504 6.985534191 -2.332076550 3.343866825 0.025353279 0.366449922 0.138545901 0.919715524
1403638589877829376 6.939430237 -2.327554941 3.344657183 0.025438501 0.366606444 0.138084874 0.919720113
1403638589927829504 6.879386902 -2.337142944 3.350020170 0.024539042 0.367627263 0.137465447 0.919429898
1403638589977829376 6.830719471 -2.332949638 3.353289366 0.025186464 0.367866129 0.137793556 0.919267714
1403638590027829504 6.775360584 -2.347182274 3.349089622 0.025368001 0.367348045 0.139663965 0.919187605
1403638590077829376 6.747772694 -2.332761049 3.356623650 0.025106041 0.367179453 0.139195502 0.919333220
1403638590127829504 6.694383621 -2.338009834 3.367773056 0.025869947 0.368299931 0.139335707 0.918842435
1403638590177829376 6.633101463 -2.341693878 3.372663260 0.026082367 0.369036704 0.138750613 0.918629348
1403638590227829504 6.593129158 -2.327300549 3.369615793 0.027273675 0.368141770 0.138335735 0.919016361
1403638590277829376 6.564304352 -2.323022604 3.375622272 0.027830323 0.367662370 0.139768690 0.918974698
1403638590327829504 6.535141945 -2.294866323 3.387352943 0.029100714 0.367641509 0.139411658 0.918997943
1403638590377829376 6.472135544 -2.281068325 3.404941320 0.028948430 0.368963271 0.138966382 0.918540359
1403638590427829504 6.389409542 -2.321859837 3.390809536 0.025199519 0.368883550 0.139832169 0.918551505
1403638590477829376 6.347521782 -2.310046196 3.391409397 0.025419770 0.368542939 0.140847340 0.918527067
1403638590527829504 6.296284676 -2.309417009 3.398287296 0.024884334 0.368281513 0.141465053 0.918551624
1403638590577829376 6.252886772 -2.298522234 3.407026529 0.023742868 0.368001431 0.142146200 0.918588996
1403638590627829504 6.204844952 -2.287135601 3.406840086 0.022451691 0.367653638 0.141849473 0.918806553
1403638590677829376 6.167940617 -2.283358574 3.422808409 0.021511337 0.367261916 0.143550888 0.918721437
1403638590727829504 6.116161346 -2.283556461 3.417778969 0.021386411 0.366864175 0.144919217 0.918668449
1403638590777829376 6.071611404 -2.279799938 3.416927338 0.020504914 0.366627216 0.144274652 0.918884575
1403638590827829504 6.020700455 -2.283283234 3.426207542 0.019494729 0.367536038 0.143443644 0.918673575
1403638590877829376 5.955597401 -2.303019524 3.416648149 0.018326025 0.367009521 0.143987253 0.918823063
1403638590927829504 5.923158169 -2.311928034 3.408033371 0.017564015 0.365565628 0.145687312 0.919145525
1403638590977829376 5.882016182 -2.311094999 3.412428141 0.017423540 0.365585804 0.146007299 0.919089377
1403638591027829504 5.848076820 -2.315245152 3.409701824 0.016509838 0.364768744 0.147253513 0.919232070
1403638591077829376 5.799708366 -2.327604055 3.411052465 0.015615346 0.365019858 0.147857293 0.919051051
1403638591127829504 5.751785278 -2.343800068 3.409004211 0.011151095 0.364987612 0.148860440 0.918966949
1403638591177829376 5.712619781 -2.334223032 3.414381027 0.008544166 0.364518166 0.149132162 0.919137180
1403638591227829504 5.676166058 -2.336084604 3.409872293 0.003168505 0.363644719 0.150621057 0.919274569
1403638591277829376 5.625369072 -2.352707148 3.413703442 -0.002783604 0.363135993 0.153945819 0.918926120
1403638591327829504 5.581212521 -2.363095760 3.417760849 -0.007951988 0.362415761 0.156750008 0.918706179
1403638591377829376 5.554781437 -2.357221127 3.420239210 -0.010244201 0.361338288 0.158801928 0.918755472
1403638591427829504 5.528275967 -2.353439093 3.429892778 -0.013095812 0.360481828 0.160350084 0.918786824
1403638591477829376 5.491874218 -2.351799965 3.445433617 -0.015347946 0.359941751 0.162007064 0.918673038
1403638591527829504 5.451193333 -2.351555347 3.450921535 -0.017519411 0.359501004 0.163751155 0.918497503
1403638591577829376 5.426134109 -2.353123665 3.465774059 -0.020560002 0.359065205 0.165590987 0.918275058
1403638591627829504 5.396014214 -2.353911638 3.478568316 -0.021284753 0.358657867 0.167052388 0.918153048
1403638591677829376 5.374289513 -2.361044884 3.486535549 -0.021551985 0.358105123 0.167775944 0.918230593
1403638591727829504 5.355467796 -2.349065781 3.503600121 -0.019323915 0.358469099 0.167761549 0.918140769
1403638591777829376 5.339836121 -2.351009607 3.523548126 -0.017711416 0.359129399 0.165864393 0.918259978
1403638591827829504 5.319228172 -2.341915131 3.552140713 -0.014712005 0.359637588 0.164933309 0.918281734
1403638591877829376 5.307604313 -2.342924595 3.564787388 -0.012958760 0.359589428 0.163063928 0.918660820
1403638591927829504 5.268555641 -2.355467558 3.583429337 -0.010136692 0.360324621 0.162411973 0.918523669
1403638591977829376 5.262553692 -2.357779264 3.603080750 -0.008335020 0.360205114 0.161597073 0.918732405
1403638592027829504 5.241069794 -2.374055386 3.626094818 -0.005225522 0.360956967 0.161413282 0.918492496
1403638592077829376 5.228259563 -2.381168365 3.646297693 -0.003328372 0.361042559 0.160495400 0.918628573
1403638592127829504 5.229159355 -2.396276236 3.660571098 -0.002021396 0.360233307 0.160156846 0.919009089
1403638592177829376 5.215222359 -2.415039062 3.686885118 0.002602461 0.358932912 0.159604147 0.919612348
1403638592227829504 5.216197491 -2.427379608 3.700589418 0.009215171 0.355562180 0.158260629 0.921110272
1403638592277829376 5.216258526 -2.443342209 3.711054802 0.016924012 0.351141334 0.157376692 0.922846615
1403638592327829504 5.204325676 -2.465110779 3.731812000 0.022630872 0.346925586 0.155699894 0.924601555
1403638592377829376 5.201630592 -2.492223501 3.750051975 0.027488107 0.340311110 0.154440999 0.927135766
1403638592427829504 5.189765930 -2.520867109 3.758628368 0.030409167 0.332454801 0.151188686 0.930425227
1403638592477829376 5.194178581 -2.545198441 3.774950504 0.031470235 0.323608458 0.149450243 0.933783591
1403638592527829504 5.187388420 -2.580388784 3.788628340 0.028827697 0.316519350 0.145932317 0.936850190
1403638592577829376 5.188110828 -2.598538160 3.785263538 0.025676338 0.309448183 0.142666906 0.939802468
1403638592627829504 5.183908463 -2.633283854 3.799357891 0.021766240 0.303694695 0.139485255 0.942252398
1403638592677829376 5.188650608 -2.656289816 3.800739765 0.018068111 0.298008174 0.137928218 0.944373071
1403638592727829504 5.189112663 -2.691222668 3.813286304 0.013534605 0.293594420 0.135870874 0.946128011
1403638592777829376 5.194876671 -2.720312119 3.825438976 0.009027568 0.289647281 0.135136977 0.947502494
1403638592827829504 5.198270798 -2.745826244 3.819865227 0.005498984 0.286038816 0.134945542 0.948652327
1403638592877829376 5.200180054 -2.763126850 3.821622372 0.002895736 0.283373326 0.134081379 0.949585915
1403638592927829504 5.205650806 -2.786608696 3.834491730 0.001381360 0.281900942 0.133390501 0.950124681
1403638592977829376 5.219262123 -2.827310562 3.862112284 -0.000861052 0.281122446 0.131366923 0.950637758
1403638593027829504 5.230901718 -2.857133150 3.877564430 -0.001020584 0.279921681 0.131949261 0.950911224
1403638593077829376 5.236300468 -2.869792938 3.891325712 -0.001038688 0.279769152 0.132287771 0.950909078
1403638593127829504 5.251306057 -2.901734114 3.904440880 -0.000534315 0.279240787 0.130866483 0.951261401
1403638593177829376 5.263782501 -2.918366909 3.914912701 0.002319185 0.279311061 0.130663753 0.951265991
1403638593227829504 5.282139778 -2.940953255 3.925959587 0.006077471 0.280744821 0.127658650 0.951235354
1403638593277829376 5.295725346 -2.967222214 3.941148996 0.007665647 0.282983363 0.123290993 0.951136649
1403638593327829504 5.321578026 -2.983762980 3.950102329 0.010502543 0.284256995 0.118941791 0.951283574
1403638593377829376 5.333933830 -3.039731979 3.982622623 0.012222144 0.287943780 0.113804311 0.950782597
1403638593427829504 5.360978127 -3.077709913 4.003998756 0.015226226 0.290340424 0.107662931 0.950725675
1403638593477829376 5.371723175 -3.097776890 4.015819073 0.019095851 0.292347759 0.105199747 0.950316370
1403638593527829504 5.383966446 -3.127113342 4.034851074 0.021342315 0.294310749 0.103567958 0.949841738
1403638593577829376 5.403848648 -3.134054184 4.035371304 0.024470679 0.295402586 0.101872273 0.949610770
1403638593627829504 5.403455734 -3.182516813 4.072544575 0.023752136 0.297772765 0.101932071 0.948881984
1403638593677829376 5.421127796 -3.184818745 4.079658031 0.025513357 0.297996968 0.099910691 0.948980868
1403638593727829504 5.443828583 -3.254802942 4.123060226 0.025314398 0.298764139 0.099420473 0.948796451
1403638593777829376 5.456274033 -3.253479719 4.137272835 0.030201914 0.299249202 0.098784946 0.948566914
1403638593827829504 5.463720798 -3.284388065 4.152642727 0.037158690 0.298761994 0.100457437 0.948297858
1403638593877829376 5.473564148 -3.312558174 4.177124977 0.047333904 0.296903372 0.100031331 0.948473275
1403638593927829504 5.480410576 -3.338641644 4.182579994 0.053363565 0.293861508 0.099979416 0.949105799
1403638593977829376 5.488162994 -3.362241745 4.212093830 0.055257253 0.290160775 0.100263409 0.950105608
1403638594027829504 5.489288807 -3.378266096 4.215940952 0.052456900 0.285962731 0.102518715 0.951295674
1403638594077829376 5.494622231 -3.407473087 4.235219955 0.049124770 0.281925768 0.104002215 0.952516735
1403638594127829504 5.499194622 -3.434865952 4.244620800 0.044401955 0.279379308 0.103302330 0.953574479
1403638594177829376 5.499177933 -3.442878962 4.246799946 0.040915035 0.277283639 0.101761214 0.954507411
1403638594227829504 5.501438141 -3.474581242 4.262999535 0.037930362 0.276316017 0.100165658 0.955079854
1403638594277829376 5.507327080 -3.489244699 4.265060902 0.037793308 0.274549663 0.098035008 0.955815494
1403638594327829504 5.505358696 -3.518925905 4.279995918 0.038138594 0.274137825 0.096191749 0.956107199
1403638594377829376 5.502810955 -3.540729284 4.278768539 0.039405286 0.274349004 0.092499092 0.956359625
1403638594427829504 5.496394157 -3.563323736 4.286446095 0.040770877 0.274684370 0.088571317 0.956577957
1403638594477829376 5.492897034 -3.589092731 4.297215462 0.041497242 0.275041819 0.085720994 0.956703663
1403638594527829504 5.494262695 -3.599631071 4.287472725 0.042368203 0.272548556 0.088169895 0.957156360
1403638594577829376 5.487042427 -3.634272575 4.301017761 0.042431548 0.271317750 0.090575226 0.957278609
1403638594627829504 5.478578568 -3.649931908 4.291952133 0.042821821 0.269407988 0.093521260 0.957517326
1403638594677829376 5.478127480 -3.698549986 4.294055462 0.041783158 0.267896295 0.096122205 0.957729757
1403638594727829504 5.470202446 -3.718766451 4.292121887 0.041451260 0.267343163 0.098042481 0.957704067
1403638594777829376 5.462028980 -3.744283438 4.299064159 0.041074313 0.267275453 0.098924272 0.957648516
1403638594827829504 5.458113670 -3.768617392 4.302255630 0.040874127 0.266902864 0.100135155 0.957635224
1403638594877829376 5.447931767 -3.785183907 4.285111904 0.041000493 0.266412556 0.100735262 0.957703352
1403638594927829504 5.438467979 -3.798086643 4.285068512 0.039658424 0.266919702 0.101244390 0.957564950
1403638594977829376 5.423432350 -3.825796127 4.292614937 0.037547432 0.267863601 0.101313263 0.957379222
1403638595027829504 5.410705566 -3.847139120 4.289735794 0.036289483 0.267568916 0.103399776 0.957287073
1403638595077829376 5.402403831 -3.854577303 4.287163734 0.035236120 0.267516375 0.103449270 0.957335711
1403638595127829504 5.383991241 -3.860368490 4.285087585 0.035074543 0.268062681 0.104739711 0.957048476
1403638595177829376 5.382266045 -3.871667862 4.289723873 0.034594353 0.267754912 0.104972929 0.957126558
1403638595227829504 5.367632389 -3.879710436 4.296571732 0.034273565 0.268751949 0.104528420 0.956907272
1403638595277829376 5.360919952 -3.888943672 4.298596859 0.033534162 0.268570811 0.104817212 0.956952751
1403638595327829504 5.349066257 -3.885953188 4.288541794 0.033968329 0.268483013 0.104199558 0.957029521
1403638595377829376 5.334264755 -3.889668465 4.297752380 0.034268875 0.268781483 0.105374113 0.956806421
1403638595427829504 5.325860500 -3.891411066 4.303482056 0.034327809 0.268822491 0.105220079 0.956809700
1403638595477829376 5.316079140 -3.890149593 4.300229073 0.033597507 0.268584192 0.105733283 0.956845999
1403638595527829504 5.299479485 -3.896982908 4.305083275 0.032973159 0.268772840 0.105189472 0.956874669
1403638595577829376 5.280128002 -3.895881414 4.310770035 0.032252487 0.268932849 0.105551586 0.956814349
1403638595627829504 5.268645287 -3.890377760 4.305480957 0.032345988 0.268960774 0.104690365 0.956897974
1403638595677829376 5.262870789 -3.891405821 4.306807518 0.032065291 0.269307137 0.102516480 0.957045376
1403638595727829504 5.251739502 -3.894369602 4.298344612 0.030795744 0.270064801 0.099689096 0.957172215
1403638595777829376 5.239097118 -3.900881290 4.302618504 0.029932532 0.270990193 0.097721852 0.957140982
1403638595827829504 5.224239349 -3.903228998 4.291648388 0.029172519 0.271361738 0.096891604 0.957143545
1403638595877829376 5.209966183 -3.905805349 4.294198990 0.029038506 0.271579206 0.096654207 0.957109988
1403638595927829504 5.197551250 -3.905403137 4.299242020 0.029305300 0.272118151 0.095944792 0.957020104
1403638595977829376 5.184546471 -3.900176287 4.303434849 0.029179100 0.272795081 0.094289124 0.956995785
1403638596027829504 5.168725967 -3.893613577 4.309501648 0.029068533 0.274003148 0.091435999 0.956930935
1403638596077829376 5.156652927 -3.886249304 4.314170837 0.026593981 0.276087016 0.086257003 0.956884801
1403638596127829504 5.135838032 -3.872286081 4.306406975 0.025404474 0.278288335 0.080459677 0.956784487
1403638596177829376 5.123479843 -3.864804029 4.314683914 0.022700049 0.280570179 0.073156394 0.956772327
1403638596227829504 5.102001667 -3.858180285 4.321959972 0.020451050 0.283038259 0.067183398 0.956534147
1403638596277829376 5.073881149 -3.853434086 4.335096359 0.018094724 0.285871059 0.059907891 0.956222415
1403638596327829504 5.054677010 -3.851866484 4.340902328 0.016811175 0.287268430 0.053825997 0.956188738
1403638596377829376 5.034088135 -3.851955414 4.342415810 0.016377050 0.288736403 0.048482075 0.956040025
1403638596427829504 4.999310493 -3.853346586 4.349268913 0.015823284 0.290055424 0.045297161 0.955806315
1403638596477829376 4.961982250 -3.852137327 4.353168488 0.016641881 0.291011065 0.041660421 0.955667317
1403638596527829504 4.930772781 -3.864312649 4.350541115 0.015212161 0.292060256 0.037614886 0.955538869
1403638596577829376 4.896678925 -3.878052473 4.364449501 0.013623407 0.293033868 0.033297032 0.955424964
1403638596627829504 4.851714134 -3.885027170 4.360537052 0.013214512 0.294483155 0.029087998 0.955122471
1403638596677829376 4.806916237 -3.905128717 4.373192310 0.011866213 0.295968026 0.024298556 0.954815030
1403638596727829504 4.757575989 -3.927609205 4.381753445 0.010481478 0.296820194 0.021323306 0.954637766
1403638596777829376 4.697045326 -3.949335337 4.402158737 0.010800001 0.297962546 0.019119106 0.954324961
1403638596827829504 4.641568661 -3.968801737 4.409387589 0.010684616 0.298630685 0.016707385 0.954162717
1403638596877829376 4.580846786 -3.995430470 4.417005539 0.011565899 0.298674494 0.014610623 0.954173148
1403638596927829504 4.517395496 -4.024001122 4.430218220 0.012170028 0.299244255 0.013099319 0.954008996
1403638596977829376 4.446917534 -4.045238495 4.439257145 0.013583282 0.299353182 0.012732531 0.953960717
1403638597027829504 4.377866745 -4.076951981 4.460612774 0.013849004 0.300061226 0.012092291 0.953742743
1403638597077829376 4.282540798 -4.106673241 4.475297451 0.014342299 0.301373243 0.010663161 0.953338742
1403638597127829504 4.193775654 -4.144068718 4.516538620 0.015100224 0.303415865 0.009673829 0.952689469
1403638597177829376 4.127375126 -4.163805962 4.509012699 0.016138544 0.302049398 0.009119386 0.953112006
1403638597227829504 4.030566216 -4.194839001 4.560812950 0.018426104 0.303515077 0.010314415 0.952592611
1403638597277829376 3.941104174 -4.226937771 4.583395958 0.020108692 0.303205013 0.012631029 0.952629447
1403638597327829504 3.830721855 -4.240061283 4.603356838 0.023416255 0.302571833 0.015951412 0.952705324
1403638597377829376 3.729195118 -4.258355141 4.638972759 0.025975993 0.302233011 0.019666547 0.952677071
1403638597427829504 3.624462843 -4.278290749 4.660605431 0.029179985 0.300829411 0.024669802 0.952912152
1403638597477829376 3.498102427 -4.306406975 4.706294537 0.033621568 0.299942404 0.030073689 0.952890158
1403638597527829504 3.404399157 -4.332138062 4.739193916 0.038664948 0.296423078 0.037324362 0.953543544
1403638597577829376 3.290154219 -4.346771240 4.796833515 0.044247296 0.295212507 0.044469722 0.953369915
1403638597627829504 3.185333490 -4.364115715 4.805747032 0.046307288 0.293009579 0.047682922 0.953796268
1403638597677829376 3.032903910 -4.386294842 4.839041233 0.048158277 0.294093341 0.050191116 0.953242242
1403638597727829504 2.926667452 -4.394744873 4.870290756 0.048091996 0.293510050 0.049487215 0.953462124
1403638597777829376 2.801791191 -4.412808895 4.921069622 0.044979606 0.294195026 0.044489194 0.953649223
1403638597827829504 2.697653770 -4.428873062 4.916050911 0.042144764 0.290797561 0.038277678 0.955089211
1403638597877829376 2.569505930 -4.434463978 4.982571125 0.040832873 0.290319473 0.031974263 0.955523372
1403638597927829504 2.467825413 -4.446226120 4.991672039 0.038107712 0.286960453 0.026090378 0.956828475
1403638597977829376 2.331464529 -4.465212345 5.021028042 0.037407663 0.284529328 0.023892600 0.957639217
1403638598027829504 2.201074123 -4.481945038 5.057196617 0.037191320 0.281735778 0.022323798 0.958510995
1403638598077829376 2.055446625 -4.501400471 5.108133793 0.039778024 0.277893364 0.025286900 0.959454834
1403638598127829504 1.937956214 -4.510578156 5.151627064 0.042172648 0.270061880 0.034583271 0.961297035
1403638598177829376 1.802521229 -4.526921272 5.166562557 0.043297157 0.263635218 0.044153553 0.962638199
1403638598227829504 1.674713492 -4.531569004 5.181793690 0.045348369 0.257179141 0.052102882 0.963891983
1403638598277829376 1.531613350 -4.560628891 5.236528873 0.043751732 0.253099680 0.060315009 0.964566469
1403638598327829504 1.331318378 -4.582771301 5.260026932 0.043435611 0.251039296 0.067938775 0.964612305
1403638598377829376 1.200500131 -4.605439663 5.285687923 0.041920405 0.247693270 0.072503500 0.965211868
1403638598427829504 1.047980666 -4.620987415 5.293895721 0.039839204 0.246486336 0.074017689 0.965494037
1403638598477829376 0.916445494 -4.632286549 5.350689888 0.038642623 0.245531246 0.075744189 0.965652108
1403638598527829504 0.785524607 -4.641910553 5.365026474 0.038576622 0.241178393 0.076923691 0.966657937
1403638598577829376 0.657896876 -4.653347492 5.377328396 0.036130480 0.236693352 0.077493042 0.967814922
1403638598627829504 0.513791680 -4.660701752 5.418951035 0.034556311 0.233697131 0.075363517 0.968768239
1403638598677829376 0.412835836 -4.665288925 5.439718246 0.034124605 0.226882428 0.072596811 0.970613003
1403638598727829504 0.260639071 -4.674283504 5.453991413 0.032986980 0.221153200 0.069373131 0.972209096
1403638598777829376 0.104272366 -4.684669018 5.474150658 0.033061814 0.213940486 0.067735225 0.973934472
1403638598827829504 -0.014085531 -4.682374001 5.485894680 0.034851830 0.205176979 0.063599117 0.976034284
1403638598877829376 -0.157758951 -4.699477196 5.512273788 0.034481734 0.197305024 0.061002191 0.977834582
1403638598927829504 -0.255451560 -4.702234745 5.539980412 0.033972647 0.187923059 0.055305697 0.980036736
1403638598977829376 -0.448142052 -4.729649067 5.563650131 0.033650469 0.180082589 0.052873492 0.981652796
1403638599027829504 -0.565746903 -4.734062672 5.571291447 0.034089804 0.169045493 0.050274517 0.983734667
1403638599077829376 -0.657626033 -4.745944500 5.574980736 0.034625281 0.156791985 0.045040809 0.985996306
1403638599127829504 -0.806042194 -4.762068748 5.589298248 0.034447376 0.147948906 0.040371079 0.987570107
1403638599177829376 -0.969260454 -4.779544830 5.629652977 0.035134312 0.139474034 0.037360214 0.988896728
1403638599227829504 -1.103911400 -4.785284519 5.638544083 0.034902506 0.129223049 0.031876970 0.990488291
1403638599277829376 -1.200196624 -4.800775528 5.642938137 0.034547925 0.117037997 0.027514169 0.992144883
1403638599327829504 -1.337380648 -4.810932159 5.647642612 0.033360757 0.106384248 0.023891171 0.993478060
1403638599377829376 -1.510571957 -4.836847782 5.696279049 0.031025756 0.099474147 0.020214282 0.994350851
1403638599427829504 -1.634839654 -4.856458664 5.696918011 0.029257907 0.090786189 0.015737461 0.995316088
1403638599477829376 -1.746937037 -4.864565372 5.705965996 0.028597243 0.082094751 0.014155065 0.996113598
1403638599527829504 -1.885441542 -4.883747101 5.728448391 0.026707431 0.077371128 0.010225270 0.996592104
1403638599577829376 -2.046999216 -4.896396160 5.757905960 0.025375444 0.074539714 0.010310452 0.996841788
1403638599627829504 -2.169808388 -4.909708500 5.765356064 0.024936754 0.070443176 0.010432137 0.997149467
1403638599677829376 -2.304447174 -4.917273045 5.790004253 0.023745626 0.067714810 0.008991422 0.997381568
1403638599727829504 -2.407937050 -4.946840286 5.760691643 0.021566628 0.064620763 0.008807669 0.997637928
1403638599777829376 -2.587861538 -4.941206455 5.830663204 0.023514546 0.067339189 0.008436544 0.997417331
1403638599827829504 -2.691968203 -4.957530975 5.842763424 0.021816630 0.065154433 0.010405259 0.997582376
1403638599877829376 -2.832993507 -4.971380711 5.852143288 0.020299766 0.065244183 0.011276773 0.997599065
1403638599927829504 -2.941160679 -4.975141048 5.878129005 0.020145323 0.063714392 0.014011127 0.997666419
1403638599977829376 -3.085513115 -4.983035088 5.916674137 0.021201914 0.064973138 0.017763108 0.997503579
1403638600027829504 -3.214420557 -4.985681057 5.931069851 0.021967730 0.064489521 0.022346126 0.997426271
1403638600077829376 -3.323395014 -5.001262665 5.943749905 0.019040205 0.062669642 0.027278032 0.997479737
1403638600127829504 -3.424546242 -5.011120796 5.946311951 0.017736195 0.059837967 0.034814894 0.997443140
1403638600177829376 -3.602914810 -5.006550312 6.020356178 0.017653478 0.059891462 0.045046765 0.997031689
1403638600227829504 -3.714601040 -5.009798527 6.037330627 0.015022598 0.057759188 0.052415177 0.996840417
1403638600277829376 -3.841444969 -5.020071507 6.055922508 0.013827574 0.056231670 0.059444230 0.996550620
1403638600327829504 -3.949120045 -5.018988132 6.088999748 0.011646890 0.054823332 0.065209590 0.996296346
1403638600377829376 -4.058969975 -5.018716812 6.107618332 0.011327475 0.053649597 0.070757568 0.995985329
1403638600427829504 -4.161320210 -5.028729916 6.126664639 0.009376165 0.051361930 0.076703347 0.995685995
1403638600477829376 -4.278271198 -5.032040596 6.177936077 0.009370031 0.051830411 0.079517715 0.995440960
1403638600527829504 -4.377244473 -5.042063236 6.204263210 0.008512841 0.052166995 0.079237930 0.995453417
1403638600577829376 -4.474592209 -5.053060055 6.229653358 0.007968630 0.052749604 0.078753315 0.995465636
1403638600627829504 -4.568127632 -5.067175388 6.253285885 0.005797681 0.052917294 0.080191247 0.995356977
1403638600677829376 -4.654773712 -5.084097385 6.273343563 0.005142448 0.051682267 0.083224423 0.995176435
1403638600727829504 -4.738918781 -5.097941399 6.304511070 0.001896404 0.052192282 0.081647031 0.995292008
1403638600777829376 -4.818641663 -5.116329670 6.326798439 -0.001398643 0.051002070 0.082511090 0.995283246
1403638600827829504 -4.899702549 -5.138128281 6.355792046 -0.005328153 0.052704271 0.077088974 0.995615959
1403638600877829376 -4.974120617 -5.159553528 6.383660793 -0.008461911 0.055092730 0.069334216 0.996035099
1403638600927829504 -5.043811798 -5.178716183 6.414990902 -0.011238622 0.058251996 0.058366582 0.996530831
1403638600977829376 -5.111457825 -5.200759411 6.444442749 -0.012547013 0.060790215 0.048998304 0.996868253
1403638601027829504 -5.180356026 -5.220257759 6.479063988 -0.013305525 0.063022576 0.041769955 0.997048855
1403638601077829376 -5.245740891 -5.240478039 6.513415337 -0.013305171 0.063814200 0.036881126 0.997191310
1403638601127829504 -5.312823772 -5.260053158 6.552072048 -0.011506988 0.065384157 0.032852937 0.997252822
1403638601177829376 -5.372230530 -5.277163982 6.593897820 -0.011140083 0.066794343 0.027242523 0.997332573
1403638601227829504 -5.432737827 -5.296140671 6.637059212 -0.006544705 0.068330802 0.021761544 0.997403860
1403638601277829376 -5.494970322 -5.312529087 6.677299976 0.000043023 0.070244715 0.014910877 0.997418344
1403638601327829504 -5.555568695 -5.333127499 6.717872620 0.006211927 0.069598123 0.011916600 0.997484565
1403638601377829376 -5.622241974 -5.352573872 6.756078720 0.009410318 0.065557949 0.012775342 0.997722626
1403638601427829504 -5.681661606 -5.374962807 6.794817448 0.014886661 0.059084553 0.014974857 0.998029649
1403638601477829376 -5.717432976 -5.392270565 6.818307877 0.018225910 0.051151879 0.016284997 0.998391747
1403638601527829504 -5.764143467 -5.404486179 6.970673561 0.025842482 0.045629565 0.014338295 0.998521149
1403638601577829376 -5.853093624 -5.444962025 6.941246510 0.027162565 0.034965899 0.009100490 0.998977840
1403638601627829504 -5.929717064 -5.473906517 6.969193935 0.028607512 0.026328975 0.003899368 0.999236286
1403638601677829376 -5.984160900 -5.500854969 7.023687363 0.030673208 0.015240498 -0.002798618 0.999409318
1403638601727829504 -6.059230328 -5.534045219 7.064243317 0.031416140 0.003251402 -0.009470533 0.999456227
1403638601777829376 -6.125277519 -5.553379059 7.142085552 0.035689455 -0.009744584 -0.016843008 0.999173462
1403638601827829504 -6.150633335 -5.584057331 7.189567089 0.037679818 -0.026021715 -0.025673531 0.998621047
1403638601877829376 -6.263808727 -5.617369175 7.196065903 0.040594507 -0.037532769 -0.033552501 0.997906566
1403638601927829504 -6.364777088 -5.656824112 7.253642082 0.040677465 -0.048157241 -0.040413003 0.997192562
1403638601977829376 -6.400399208 -5.686355114 7.289078236 0.041390963 -0.062298752 -0.045521878 0.996159315
1403638602027829504 -6.462602615 -5.725352764 7.324274063 0.040155586 -0.073254436 -0.049861252 0.995256305
1403638602077829376 -6.540471077 -5.748544693 7.369945526 0.040630464 -0.081339106 -0.054079887 0.994388521
1403638602127829504 -6.602865219 -5.777484417 7.402418137 0.042123701 -0.088309258 -0.058937605 0.993455291
1403638602177829376 -6.625972271 -5.791073799 7.450211525 0.045629863 -0.098047763 -0.063801132 0.992085695
1403638602227829504 -6.703083992 -5.816142559 7.484718323 0.049242627 -0.104439594 -0.069700487 0.990862966
1403638602277829376 -6.760111809 -5.836679935 7.517992973 0.053006653 -0.114259712 -0.074985743 0.989197731
1403638602327829504 -6.809473038 -5.858814716 7.552958012 0.059286587 -0.126434162 -0.076846436 0.987215340
1403638602377829376 -6.864405632 -5.859779835 7.593523026 0.067830451 -0.142313167 -0.073042370 0.984789729
1403638602427829504 -6.925100327 -5.898112774 7.608724594 0.079753958 -0.158718973 -0.068266444 0.981726706
1403638602477829376 -7.089284897 -5.942330360 7.639523983 0.096365832 -0.169503644 -0.061821308 0.978856623
1403638602527829504 -7.155654430 -5.980433941 7.660982609 0.110308565 -0.186300218 -0.054665506 0.974749148
1403638602577829376 -7.236549854 -5.991127014 7.692498207 0.123957507 -0.201566070 -0.047270939 0.970448911
1403638602627829504 -7.303381920 -6.019610405 7.705401897 0.130163863 -0.214718506 -0.045575861 0.966889918
1403638602677829376 -7.363142490 -6.039750099 7.712023735 0.132122219 -0.226157799 -0.047472626 0.963920474
1403638602727829504 -7.419607639 -6.062808990 7.715724468 0.131807551 -0.237224653 -0.050928276 0.961123049
1403638602777829376 -7.474676609 -6.086410046 7.714276314 0.129895598 -0.246223688 -0.058150850 0.958707213
1403638602827829504 -7.502786636 -6.109251022 7.705145836 0.128445476 -0.257435441 -0.064352393 0.955556154
1403638602877829376 -7.565792084 -6.132635117 7.701844692 0.125861555 -0.267435879 -0.068631262 0.952851892
1403638602927829504 -7.621091366 -6.151577950 7.690368652 0.120915897 -0.278194129 -0.071162939 0.950222731
1403638602977829376 -7.658585548 -6.163605213 7.679353714 0.115507759 -0.292227745 -0.070143208 0.946752787
1403638603027829504 -7.741872787 -6.279605865 7.578237534 0.106192306 -0.302625477 -0.071724534 0.944455683
1403638603077829376 -7.767183781 -6.269154072 7.588334084 0.107629217 -0.314936340 -0.073975019 0.940084457
1403638603127829504 -7.744635105 -6.216563225 7.615760803 0.113727458 -0.328864396 -0.073612094 0.934609830
1403638603177829376 -7.766088486 -6.211146355 7.612779617 0.114532962 -0.337433219 -0.077496909 0.931136489
1403638603227829504 -7.784866333 -6.222293854 7.589586258 0.106779926 -0.343378931 -0.083940826 0.929323912
1403638603277829376 -7.803934097 -6.222447872 7.562334061 0.095138222 -0.346674204 -0.091668069 0.928634882
1403638603327829504 -7.827473640 -6.218679905 7.540537357 0.081606604 -0.348362565 -0.099929295 0.928438485
1403638603377829376 -7.841087818 -6.226599216 7.512166023 0.068821080 -0.349844009 -0.106964581 0.928133309
1403638603427829504 -7.859056950 -6.219774246 7.490714073 0.059050228 -0.350854397 -0.111650065 0.927873075
1403638603477829376 -7.868395329 -6.215635777 7.467588902 0.052239388 -0.351769775 -0.114386380 0.927601635
1403638603527829504 -7.880498886 -6.210907936 7.436971188 0.050461229 -0.352568537 -0.117216170 0.927043438
1403638603577829376 -7.890473366 -6.207690239 7.411633968 0.053171590 -0.355303586 -0.117962845 0.925752044
1403638603627829504 -7.894780636 -6.201726437 7.392619133 0.058055695 -0.358134985 -0.116933271 0.924497426
1403638603677829376 -7.906638622 -6.187301159 7.377023220 0.064483702 -0.358982474 -0.118277185 0.923571289
1403638603727829504 -7.916075230 -6.178475857 7.356004715 0.071166374 -0.357953340 -0.123147577 0.922843099
1403638603777829376 -7.926681519 -6.164259911 7.331606865 0.077774666 -0.356438428 -0.127947450 0.922242999
1403638603827829504 -7.934203625 -6.148399353 7.315636635 0.083571397 -0.355335742 -0.131820589 0.921615779
1403638603877829376 -7.938672066 -6.132163525 7.295006275 0.090181284 -0.353560776 -0.136502936 0.920993507
1403638603927829504 -7.941536903 -6.114301682 7.271055698 0.094744258 -0.351985037 -0.139961243 0.920619845
1403638603977829376 -7.946766853 -6.094413757 7.249003410 0.101173617 -0.350930601 -0.142264724 0.919984996
1403638604027829504 -7.948512077 -6.074240685 7.221390724 0.103055201 -0.348957241 -0.145716891 0.919986427
1403638604077829376 -7.951828003 -6.047521591 7.193159103 0.106946670 -0.347321659 -0.147808388 0.919827580
1403638604127829504 -7.953277588 -6.021359444 7.161252022 0.108490959 -0.346693128 -0.149513453 0.919608235
1403638604177829376 -7.955891132 -5.996604919 7.131345749 0.107939571 -0.347177118 -0.149057359 0.919564605
1403638604227829504 -7.957430363 -5.978397369 7.092659950 0.105894662 -0.348919451 -0.146170735 0.919606268
1403638604277829376 -7.958557129 -5.952944279 7.048629761 0.101672560 -0.350482404 -0.142475098 0.920068264
1403638604327829504 -7.957966805 -5.932927132 7.000654221 0.095397852 -0.352332443 -0.138804600 0.920594633
1403638604377829376 -7.955646992 -5.905725479 6.953613281 0.089165263 -0.353789747 -0.136253685 0.921041429
1403638604427829504 -7.954674721 -5.884039402 6.903035641 0.082645059 -0.353974551 -0.135611668 0.921673119
1403638604477829376 -7.949030876 -5.864638329 6.849095821 0.076171376 -0.353074729 -0.137912244 0.922234416
1403638604527829504 -7.948217392 -5.845639229 6.800839901 0.070257314 -0.353118420 -0.137934327 0.922683835
1403638604577829376 -7.938726902 -5.830435753 6.742074490 0.067892842 -0.352751344 -0.140225872 0.922655821
1403638604627829504 -7.936887264 -5.804444790 6.692566872 0.064635135 -0.353028268 -0.138582870 0.923032045
1403638604677829376 -7.933769703 -5.783750534 6.626726151 0.062097389 -0.353594452 -0.137007013 0.923224807
1403638604727829504 -7.929761887 -5.756657600 6.583861351 0.060402349 -0.354857802 -0.134444699 0.923229158
1403638604777829376 -7.926345825 -5.730506897 6.532879829 0.059304427 -0.355790973 -0.131885320 0.923310399
1403638604827829504 -7.927593231 -5.711379051 6.479197502 0.056335684 -0.356092364 -0.130622104 0.923559666
1403638604877829376 -7.918675900 -5.685821056 6.425674438 0.053432059 -0.355998069 -0.130933642 0.923724413
1403638604927829504 -7.911804676 -5.665836334 6.368844509 0.049288556 -0.355096012 -0.132866681 0.924025893
1403638604977829376 -7.905692101 -5.642848492 6.318658829 0.043314621 -0.354982406 -0.133849725 0.924227059
1403638605027829504 -7.901997089 -5.625124931 6.261389256 0.036752887 -0.354299128 -0.135822088 0.924485624
1403638605077829376 -7.895728588 -5.608333588 6.208052635 0.031495210 -0.353867888 -0.137296855 0.924627006
1403638605127829504 -7.882303715 -5.593008518 6.158082962 0.026503613 -0.354228139 -0.138024971 0.924537241
1403638605177829376 -7.881845474 -5.579221725 6.099359512 0.023917735 -0.353156179 -0.139799073 0.924751222
1403638605227829504 -7.881296635 -5.569488049 6.050004959 0.022683484 -0.352124274 -0.141929924 0.924851239
1403638605277829376 -7.878110409 -5.553859711 5.998869896 0.022162167 -0.351053178 -0.144318670 0.924901426
1403638605327829504 -7.873998642 -5.539029598 5.958072186 0.024517667 -0.350146383 -0.147062212 0.924753547
1403638605377829376 -7.876601696 -5.524001598 5.912592411 0.030442899 -0.348434001 -0.151463583 0.924513817
1403638605427829504 -7.876256943 -5.513216972 5.859608650 0.037007727 -0.346160859 -0.155885816 0.924393177
1403638605477829376 -7.867468357 -5.501672745 5.818966866 0.046306625 -0.345343143 -0.160020560 0.923573077
1403638605527829504 -7.869491577 -5.484599113 5.774528503 0.053591922 -0.343793631 -0.163625538 0.923125386
1403638605577829376 -7.876754761 -5.465961933 5.735267162 0.060193632 -0.342311174 -0.167675763 0.922542453
1403638605627829504 -7.881963730 -5.448533535 5.686726093 0.065453574 -0.340417802 -0.171616897 0.922160089
1403638605677829376 -7.875468254 -5.431048393 5.644320488 0.068842165 -0.340389371 -0.173254356 0.921617448
1403638605727829504 -7.884301662 -5.416318417 5.592814445 0.070038632 -0.339679539 -0.175214306 0.921418667
1403638605777829376 -7.893616676 -5.392147541 5.549686909 0.070290156 -0.339760065 -0.175363600 0.921341419
1403638605827829504 -7.906125546 -5.377986908 5.496790886 0.069414936 -0.338841796 -0.176326379 0.921562195
1403638605877829376 -7.915564537 -5.368144035 5.440930367 0.069812618 -0.338046521 -0.178632408 0.921380103
1403638605927829504 -7.928072929 -5.348706722 5.387621403 0.070399530 -0.337116629 -0.179610178 0.921486020
1403638605977829376 -7.934073925 -5.334698200 5.335931301 0.071467958 -0.336551547 -0.181543961 0.921231389
1403638606027829504 -7.958937645 -5.317063332 5.279255390 0.071607716 -0.335196882 -0.182992250 0.921427846
1403638606077829376 -7.968911171 -5.307917595 5.214292526 0.071337633 -0.334336936 -0.185055301 0.921349168
1403638606127829504 -7.983994484 -5.284792900 5.157691479 0.071807869 -0.333748609 -0.185605988 0.921415210
1403638606177829376 -8.001255035 -5.269423008 5.099902630 0.071681380 -0.332960933 -0.187802777 0.921264887
1403638606227829504 -8.029590607 -5.247225761 5.039988518 0.071106277 -0.331607282 -0.189071998 0.921537995
1403638606277829376 -8.048544884 -5.222383022 4.982153893 0.070109606 -0.331426233 -0.189226046 0.921647906
1403638606327829504 -8.084924698 -5.188314915 4.927342892 0.066121988 -0.332128584 -0.186112985 0.922323406
1403638606377829376 -8.095442772 -5.169883251 4.852193832 0.056631718 -0.334285557 -0.181396961 0.923114955
1403638606427829504 -8.126213074 -5.137013912 4.790718079 0.049241610 -0.335731566 -0.176793188 0.923906803
1403638606477829376 -8.157583237 -5.104018211 4.736908436 0.040859733 -0.337901801 -0.171330661 0.924553216
1403638606527829504 -8.191276550 -5.070002556 4.664419651 0.032460850 -0.339781255 -0.165792271 0.925207019
1403638606577829376 -8.205476761 -5.036242485 4.608887672 0.025923375 -0.343363404 -0.162642926 0.924649596
1403638606627829504 -8.232961655 -5.007703304 4.546840668 0.019936813 -0.346391439 -0.161319405 0.923900187
1403638606677829376 -8.264451981 -4.965394020 4.490299225 0.016713772 -0.350357473 -0.160980061 0.922526836
1403638606727829504 -8.298439026 -4.928761005 4.433274269 0.011960149 -0.354634970 -0.163889229 0.920451701
1403638606777829376 -8.338986397 -4.893773079 4.376862049 0.008961256 -0.359977812 -0.165917471 0.918045223
1403638606827829504 -8.376460075 -4.860989094 4.325924873 0.006188304 -0.366831362 -0.169853330 0.914629042
1403638606877829376 -8.407819748 -4.826809883 4.268067360 0.003031491 -0.375467211 -0.171992645 0.910732508
1403638606927829504 -8.461802483 -4.787725449 4.218336105 0.003338602 -0.383440942 -0.176740035 0.906490386
1403638606977829376 -8.513999939 -4.750474453 4.165334702 0.002575057 -0.392503113 -0.179541707 0.902052939
1403638607027829504 -8.552336693 -4.729388714 4.114089966 0.001775935 -0.403184325 -0.182075307 0.896820962
1403638607077829376 -8.582916260 -4.709407806 4.065366268 0.001025860 -0.414162129 -0.183790177 0.891453803
1403638607127829504 -8.635470390 -4.690597057 4.028587818 0.000582505 -0.425301850 -0.181389362 0.886688173
1403638607177829376 -8.682231903 -4.662081718 3.973192692 0.007217892 -0.432704866 -0.181706518 0.883004606
1403638607227829504 -8.738875389 -4.648918152 3.939589739 0.012966391 -0.440971702 -0.179946095 0.879201472
1403638607277829376 -8.792287827 -4.628479004 3.891841412 0.021458533 -0.446683854 -0.178337321 0.876475275
1403638607327829504 -8.847495079 -4.608836174 3.832255840 0.025546130 -0.451225460 -0.174412593 0.874827564
1403638607377829376 -8.905343056 -4.582871437 3.801748991 0.029926555 -0.456393003 -0.171381146 0.872604370
1403638607427829504 -8.956891060 -4.562096596 3.762734175 0.032119472 -0.459664285 -0.170376822 0.871004522
1403638607477829376 -9.005084038 -4.530531406 3.725897312 0.031668302 -0.462051332 -0.168932348 0.870038807
1403638607527829504 -9.056232452 -4.509915829 3.695784092 0.031105168 -0.464161843 -0.168346971 0.869048655
1403638607577829376 -9.110142708 -4.477337360 3.675041437 0.032002423 -0.466072828 -0.169747531 0.867719829
1403638607627829504 -9.159386635 -4.450417042 3.621090889 0.032609850 -0.465607435 -0.169302449 0.868034005
1403638607677829376 -9.216147423 -4.417071819 3.607599974 0.034390606 -0.466662616 -0.169044524 0.867448688
1403638607727829504 -9.268505096 -4.394126415 3.580969572 0.036226608 -0.466238409 -0.169850066 0.867444694
1403638607777829376 -9.313913345 -4.368385792 3.559635162 0.036632504 -0.466012806 -0.170080945 0.867503643
1403638607827829504 -9.354355812 -4.334626675 3.524766922 0.036216818 -0.465433270 -0.169957861 0.867856324
1403638607877829376 -9.413924217 -4.308584690 3.509981155 0.033506788 -0.465693831 -0.167605191 0.868282795
1403638607927829504 -9.455654144 -4.274601936 3.486627579 0.029514218 -0.466179341 -0.165041402 0.868658185
1403638607977829376 -9.501375198 -4.240564346 3.463322401 0.027318804 -0.465955466 -0.163251892 0.869188130
1403638608027829504 -9.548451424 -4.210670948 3.459342241 0.028308660 -0.466913462 -0.161221981 0.869021237
1403638608077829376 -9.598039627 -4.173969746 3.443435192 0.031219803 -0.465968221 -0.160958305 0.869477630
1403638608127829504 -9.640977859 -4.142394543 3.426989555 0.034418635 -0.464847445 -0.161249191 0.869902849
1403638608177829376 -9.683280945 -4.110082626 3.409889460 0.037753329 -0.462824255 -0.163399845 0.870441794
1403638608227829504 -9.725041389 -4.072895527 3.408688545 0.042946629 -0.462447286 -0.163942963 0.870299280
1403638608277829376 -9.763561249 -4.038629532 3.401760578 0.047195021 -0.462173164 -0.163745940 0.870261967
1403638608327829504 -9.807003975 -3.996132851 3.390149832 0.052982546 -0.461820096 -0.162834242 0.870287359
1403638608377829376 -9.848093033 -3.961578131 3.380275488 0.058002289 -0.461413473 -0.162931144 0.870164812
1403638608427829504 -9.885214806 -3.926482677 3.374444485 0.058983590 -0.461872041 -0.162114486 0.870008111
1403638608477829376 -9.923299789 -3.890323877 3.365479469 0.057836786 -0.461869568 -0.162713021 0.869974673
1403638608527829504 -9.959758759 -3.847954988 3.365615129 0.055990428 -0.461892158 -0.163782597 0.869882762
1403638608577829376 -9.996797562 -3.803833485 3.350975037 0.056060281 -0.460989088 -0.164399564 0.870240808
1403638608627829504 -10.031130791 -3.763997555 3.346333265 0.058054488 -0.462462425 -0.161026940 0.869958937
1403638608677829376 -10.066133499 -3.726310492 3.336981773 0.060115259 -0.464079171 -0.158177152 0.869480729
1403638608727829504 -10.093091965 -3.683184385 3.332434654 0.062240284 -0.465044469 -0.156755611 0.869072795
1403638608777829376 -10.119099617 -3.637507677 3.305584431 0.061083611 -0.463716865 -0.157899514 0.869656920
1403638608827829504 -10.155209541 -3.610520363 3.317790508 0.057497367 -0.465123236 -0.159222469 0.868908882
1403638608877829376 -10.180532455 -3.572933674 3.301190615 0.054316964 -0.464810967 -0.160139605 0.869112015
1403638608927829504 -10.204109192 -3.537511587 3.284327984 0.050994653 -0.464481711 -0.161263123 0.869281590
1403638608977829376 -10.226741791 -3.505939007 3.278578758 0.047016233 -0.465314001 -0.160917580 0.869124770
1403638609027829504 -10.249885559 -3.475578547 3.259469509 0.043794278 -0.465315074 -0.160700515 0.869332671
1403638609077829376 -10.269137383 -3.445667028 3.242387295 0.041908111 -0.464740187 -0.161456525 0.869593024
1403638609127829504 -10.289460182 -3.423313618 3.238952875 0.041242611 -0.465373486 -0.162255585 0.869137347
1403638609177829376 -10.309738159 -3.399218798 3.227031231 0.041012693 -0.466514111 -0.159523681 0.869042456
1403638609227829504 -10.330396652 -3.371949911 3.207902431 0.041406870 -0.468311608 -0.154443488 0.868974686
1403638609277829376 -10.352609634 -3.353657722 3.200659275 0.040307857 -0.470070451 -0.150463358 0.868774891
1403638609327829504 -10.370123863 -3.320623875 3.192218304 0.040461838 -0.470393509 -0.149455532 0.868766844
1403638609377829376 -10.384588242 -3.294165134 3.182852745 0.040538441 -0.469681025 -0.151456952 0.868802190
1403638609427829504 -10.396858215 -3.265945911 3.184132099 0.040944632 -0.469455272 -0.153387949 0.868566334
1403638609477829376 -10.410093307 -3.238206387 3.171927214 0.040361814 -0.468098193 -0.155469894 0.868955791
1403638609527829504 -10.420528412 -3.202833176 3.166568279 0.040665906 -0.467278302 -0.157104552 0.869088829
1403638609577829376 -10.431474686 -3.168067455 3.158482552 0.040828947 -0.466102093 -0.158906400 0.869385183
1403638609627829504 -10.439702988 -3.132614136 3.146096945 0.040756591 -0.465522140 -0.158613488 0.869752765
1403638609677829376 -10.453344345 -3.099279881 3.161073685 0.042754374 -0.465764105 -0.161824405 0.868935406
1403638609727829504 -10.455784798 -3.056929827 3.151198387 0.043551065 -0.464796990 -0.162904456 0.869211853
1403638609777829376 -10.469531059 -3.027650833 3.153431177 0.042194206 -0.464784622 -0.163041562 0.869259655
1403638609827829504 -10.474191666 -2.996927500 3.145226240 0.040659223 -0.464933693 -0.162418589 0.869369745
1403638609877829376 -10.484857559 -2.972416162 3.155245304 0.041275550 -0.465418994 -0.163086548 0.868955851
1403638609927829504 -10.486311913 -2.941848040 3.168667078 0.041826364 -0.466480821 -0.162607551 0.868449748
1403638609977829376 -10.491071701 -2.918625832 3.170170784 0.042407695 -0.467073947 -0.162010670 0.868214309
1403638610027829504 -10.497861862 -2.898874760 3.162406445 0.042994987 -0.467516899 -0.160332978 0.868258476
1403638610077829376 -10.502370834 -2.871886492 3.154894352 0.046308536 -0.467721701 -0.157913536 0.868421137
1403638610127829504 -10.501939774 -2.851249218 3.156282902 0.048427183 -0.468492478 -0.156664327 0.868116260
1403638610177829376 -10.503290176 -2.827100039 3.146962166 0.051785082 -0.467701495 -0.156696156 0.868343174
1403638610227829504 -10.500814438 -2.804999828 3.143980503 0.053055003 -0.468484432 -0.154807657 0.868183196
1403638610277829376 -10.498451233 -2.782997608 3.150103807 0.053928543 -0.469263226 -0.153636441 0.867916822
1403638610327829504 -10.497641563 -2.762269735 3.154524326 0.054467797 -0.469607502 -0.153908491 0.867648661
1403638610377829376 -10.494230270 -2.728135824 3.147536039 0.054600187 -0.469519913 -0.152697325 0.867901742
1403638610427829504 -10.488124847 -2.704472780 3.146226645 0.055100456 -0.469512582 -0.151737168 0.868042469
1403638610477829376 -10.482742310 -2.677359343 3.150638819 0.056909442 -0.469197571 -0.152603135 0.867944241
1403638610527829504 -10.473860741 -2.659636736 3.158550501 0.059472904 -0.469653606 -0.153085887 0.867440581
1403638610577829376 -10.463329315 -2.620615005 3.163907051 0.066048414 -0.470831275 -0.150144562 0.866840303
1403638610627829504 -10.452562332 -2.590903759 3.154497623 0.072137952 -0.471147090 -0.146952361 0.866730392
1403638610677829376 -10.441539764 -2.563740015 3.158982754 0.073571764 -0.471939623 -0.145214871 0.866471469
1403638610727829504 -10.426331520 -2.528151274 3.155617952 0.070463553 -0.471653610 -0.146920457 0.866598010
1403638610777829376 -10.406865120 -2.509191036 3.159260988 0.063957989 -0.472067207 -0.149188474 0.866489828
1403638610827829504 -10.388356209 -2.489522696 3.171667814 0.056420844 -0.472568542 -0.152017385 0.866248429
1403638610877829376 -10.367944717 -2.460179329 3.146752596 0.051158309 -0.471037388 -0.153931558 0.867070735
1403638610927829504 -10.341923714 -2.435687304 3.157995939 0.050396238 -0.472400010 -0.154663026 0.866243482
1403638610977829376 -10.318243027 -2.417302847 3.154364109 0.050391119 -0.472848982 -0.154446170 0.866037488
1403638611027829504 -10.295507431 -2.388821602 3.148573875 0.052010983 -0.473575979 -0.151901528 0.865994513
1403638611077829376 -10.270328522 -2.371165276 3.156182289 0.055050615 -0.474719763 -0.151438937 0.865261137
1403638611127829504 -10.240118027 -2.343357325 3.143793821 0.055896632 -0.475154847 -0.150117114 0.865198374
1403638611177829376 -10.213495255 -2.318595886 3.141866446 0.055528816 -0.475251973 -0.150993451 0.865016222
1403638611227829504 -10.179902077 -2.291203499 3.142070293 0.056063775 -0.475558221 -0.151273385 0.864764452
1403638611277829376 -10.150786400 -2.270262241 3.151991129 0.055874269 -0.476152331 -0.152351350 0.864260435
1403638611327829504 -10.120250702 -2.246317387 3.135288000 0.056342617 -0.474140793 -0.154912591 0.864880383
1403638611377829376 -10.085017204 -2.221587658 3.134338617 0.059646957 -0.472305298 -0.159468770 0.864835024
1403638611427829504 -10.045514107 -2.204156399 3.141216755 0.064326257 -0.469726920 -0.167290822 0.864426136
1403638611477829376 -10.010595322 -2.182373285 3.128937721 0.066915147 -0.466569394 -0.173187748 0.864778221
1403638611527829504 -9.976462364 -2.157178402 3.115405083 0.069333620 -0.463411659 -0.178691223 0.865165830
1403638611577829376 -9.932170868 -2.140052319 3.117126942 0.068273671 -0.462151140 -0.182554737 0.865117788
1403638611627829504 -9.895392418 -2.129943848 3.101592541 0.065976523 -0.460919231 -0.183994442 0.865648091
1403638611677829376 -9.853350639 -2.107323170 3.098095179 0.064855628 -0.461150438 -0.183924019 0.865624607
1403638611727829504 -9.820515633 -2.096588135 3.082216740 0.059696488 -0.461905956 -0.181592271 0.866085172
1403638611777829376 -9.782949448 -2.082011700 3.067265749 0.054480117 -0.463386089 -0.177401379 0.866506815
1403638611827829504 -9.738407135 -2.056256294 3.057187080 0.050638143 -0.464804232 -0.173762605 0.866717577
1403638611877829376 -9.699438095 -2.032042503 3.042356968 0.046090420 -0.465587556 -0.170399204 0.867218554
1403638611927829504 -9.664754868 -2.016875029 3.032114506 0.042332105 -0.465918958 -0.168533579 0.867596626
1403638611977829376 -9.627002716 -1.996748447 3.012406826 0.039475404 -0.466085613 -0.166920394 0.867953598
1403638612027829504 -9.585597038 -1.972083330 3.010770798 0.037996419 -0.466594517 -0.166344479 0.867856741
1403638612077829376 -9.546854973 -1.952561140 3.001907587 0.036814749 -0.466042370 -0.167242065 0.868031859
1403638612127829504 -9.508832932 -1.934433460 2.979296207 0.034466229 -0.466377974 -0.164149508 0.868538201
1403638612177829376 -9.468463898 -1.911648631 2.969112635 0.035074204 -0.465671480 -0.164992034 0.868733287
1403638612227829504 -9.427793503 -1.896682739 2.965619087 0.034370173 -0.466037303 -0.164825991 0.868596733
1403638612277829376 -9.384092331 -1.885527015 2.963663816 0.035566013 -0.466677010 -0.164717019 0.868225694
1403638612327829504 -9.342251778 -1.875300646 2.945400238 0.034750555 -0.465832472 -0.165759787 0.868513823
1403638612377829376 -9.304385185 -1.864720106 2.939834356 0.036162283 -0.465385675 -0.165987477 0.868652165
1403638612427829504 -9.263614655 -1.842782259 2.927877188 0.037656073 -0.464868456 -0.165961996 0.868870497
1403638612477829376 -9.219865799 -1.830737114 2.919779539 0.039718628 -0.464273691 -0.165835053 0.869120836
1403638612527829504 -9.178367615 -1.812292218 2.909326077 0.042441439 -0.462890536 -0.167098939 0.869487822
1403638612577829376 -9.137638092 -1.803349257 2.905678511 0.044175901 -0.462118089 -0.168207482 0.869598508
1403638612627829504 -9.095886230 -1.785649896 2.894984722 0.045665756 -0.459913135 -0.171412572 0.870064497
1403638612677829376 -9.056305885 -1.769911289 2.892097473 0.048040804 -0.458332360 -0.173740938 0.870308936
1403638612727829504 -9.013547897 -1.749845982 2.890042543 0.049657360 -0.457112044 -0.175125480 0.870582461
1403638612777829376 -8.973636627 -1.726338863 2.883235455 0.051284727 -0.455921680 -0.175268009 0.871083498
1403638612827829504 -8.933843613 -1.704413414 2.876068592 0.052872926 -0.455084622 -0.174196035 0.871641099
1403638612877829376 -8.892148972 -1.699488878 2.876631498 0.053705387 -0.455113709 -0.173763528 0.871661305
1403638612927829504 -8.851495743 -1.682904720 2.865059137 0.053679392 -0.454808235 -0.172282726 0.872116208
1403638612977829376 -8.809976578 -1.664067507 2.860890388 0.053389929 -0.454945654 -0.171610743 0.872194767
1403638613027829504 -8.767129898 -1.635481000 2.841656685 0.050734092 -0.454181910 -0.171415418 0.872789562
1403638613077829376 -8.733171463 -1.624921918 2.828411102 0.049351070 -0.454150915 -0.170331672 0.873097122
1403638613127829504 -8.687526703 -1.616170287 2.809334755 0.048058141 -0.453575075 -0.170900226 0.873357475
1403638613177829376 -8.647729874 -1.595515609 2.803121090 0.045721445 -0.453991324 -0.170300677 0.873383760
1403638613227829504 -8.603146553 -1.573672771 2.782248259 0.046660967 -0.453363746 -0.170147002 0.873689950
1403638613277829376 -8.556442261 -1.560970783 2.762075424 0.046024673 -0.452878326 -0.170726582 0.873862326
1403638613327829504 -8.516774178 -1.543578982 2.743650436 0.046398412 -0.452437699 -0.171403453 0.873938322
1403638613377829376 -8.475433350 -1.542708874 2.726308823 0.046781797 -0.452470422 -0.171609715 0.873860478
1403638613427829504 -8.432443619 -1.547678471 2.722526550 0.045946125 -0.453084677 -0.172087520 0.873492479
1403638613477829376 -8.385324478 -1.539064050 2.713246346 0.047808670 -0.453572810 -0.171188757 0.873315811
1403638613527829504 -8.347324371 -1.528712988 2.698859692 0.048599198 -0.452536196 -0.169334441 0.874171019
1403638613577829376 -8.306431770 -1.509033918 2.679134369 0.049065396 -0.450258255 -0.167960480 0.875585139
1403638613627829504 -8.263154030 -1.497682095 2.653554201 0.049417358 -0.449851900 -0.163276613 0.876659572
1403638613677829376 -8.225294113 -1.485076666 2.657076120 0.051003750 -0.449899495 -0.161153674 0.876937032
1403638613727829504 -8.187129021 -1.482847214 2.651637077 0.053533986 -0.450628668 -0.156687006 0.877221286
1403638613777829376 -8.141029358 -1.466439486 2.622075319 0.055159688 -0.448769599 -0.153341487 0.878663599
1403638613827829504 -8.098864555 -1.424658895 2.607058287 0.058143400 -0.445600420 -0.150017738 0.880655587
1403638613877829376 -8.057350159 -1.419716120 2.602206230 0.058273356 -0.441640615 -0.147864178 0.883002818
1403638613927829504 -8.006097794 -1.382863045 2.576004505 0.058800876 -0.435696870 -0.145552933 0.886298537
1403638613977829376 -7.958333015 -1.354248524 2.567064762 0.058574818 -0.429124951 -0.143294528 0.889880538
1403638614027829504 -7.914957523 -1.327651858 2.549736977 0.058826141 -0.420333773 -0.142808348 0.894127965
1403638614077829376 -7.863086700 -1.305846810 2.548512459 0.057078011 -0.412567109 -0.140220717 0.898258626
1403638614127829504 -7.815728664 -1.275445104 2.536893368 0.056170717 -0.402492702 -0.139028534 0.903058946
1403638614177829376 -7.764725685 -1.252276540 2.518156052 0.053348564 -0.392532766 -0.137605563 0.907819748
1403638614227829504 -7.714819908 -1.222938061 2.503662109 0.052156229 -0.383228332 -0.135244295 0.912208676
1403638614277829376 -7.663716793 -1.197564960 2.487660885 0.050351094 -0.375301898 -0.132404655 0.916014314
1403638614327829504 -7.609976768 -1.181017041 2.471682549 0.048208237 -0.368480176 -0.130762905 0.919129670
1403638614377829376 -7.557583332 -1.157896519 2.449136019 0.046842426 -0.362412483 -0.129009038 0.921856582
1403638614427829504 -7.505415916 -1.144051075 2.437029362 0.045200959 -0.358648896 -0.125956938 0.923830450
1403638614477829376 -7.454041958 -1.126752019 2.415508509 0.044326156 -0.354933172 -0.123714529 0.925609171
1403638614527829504 -7.401992798 -1.112280607 2.394024134 0.042972069 -0.351484120 -0.120748334 0.927379191
1403638614577829376 -7.348196983 -1.099323511 2.372551680 0.042287115 -0.346971124 -0.118831545 0.929355621
1403638614627829504 -7.295261383 -1.093676090 2.355103493 0.041251071 -0.343080461 -0.114239976 0.931420088
1403638614677829376 -7.240651131 -1.083848357 2.327689171 0.040036906 -0.337533712 -0.110167019 0.933986783
1403638614727829504 -7.185524940 -1.079159856 2.305139303 0.036128350 -0.332867324 -0.103723571 0.936555088
1403638614777829376 -7.131540298 -1.070624471 2.276214838 0.031432673 -0.326318562 -0.097469054 0.939695656
1403638614827829504 -7.075765610 -1.069310904 2.260242939 0.027426269 -0.318966210 -0.092041716 0.942887425
1403638614877829376 -7.013557434 -1.073092818 2.244077444 0.021501301 -0.311082751 -0.086605236 0.946184337
1403638614927829504 -6.957516670 -1.069723964 2.214392662 0.020392068 -0.300035298 -0.082974933 0.950093746
1403638614977829376 -6.898881912 -1.070836067 2.191774845 0.018252216 -0.288720578 -0.078083515 0.954049408
1403638615027829504 -6.835988045 -1.083501101 2.174163342 0.016967870 -0.276405543 -0.073713258 0.958059728
1403638615077829376 -6.774968147 -1.088034749 2.152070522 0.018029541 -0.261852115 -0.070667952 0.962348342
1403638615127829504 -6.712678432 -1.098750591 2.133665800 0.019763459 -0.246534854 -0.067411788 0.966584504
1403638615177829376 -6.656114578 -1.109497070 2.118511677 0.025224322 -0.230823398 -0.064191513 0.970548153
1403638615227829504 -6.595753193 -1.122603655 2.094545841 0.029071705 -0.213160351 -0.063745871 0.974501908
1403638615277829376 -6.530768394 -1.137332201 2.081792831 0.032824617 -0.197024122 -0.060141820 0.978001535
1403638615327829504 -6.465328217 -1.151966095 2.074310303 0.035091713 -0.181745663 -0.055557046 0.981147528
1403638615377829376 -6.397770882 -1.174640536 2.072011709 0.035793401 -0.165990293 -0.050688818 0.984173119
1403638615427829504 -6.332535744 -1.177417278 2.060488939 0.039106477 -0.150458321 -0.045910358 0.986775160
1403638615477829376 -6.275297165 -1.192360401 2.046282768 0.039027911 -0.133568242 -0.039000869 0.989502549
1403638615527829504 -6.211187363 -1.195584774 2.036941051 0.039819315 -0.118481979 -0.033748712 0.991583347
1403638615577829376 -6.150836468 -1.204301476 2.011993885 0.039913978 -0.105159678 -0.027938427 0.993261218
1403638615627829504 -6.072092533 -1.218665719 2.001675129 0.038434524 -0.095811114 -0.022768551 0.994396567
1403638615677829376 -6.010525703 -1.217993736 1.986962914 0.038725033 -0.086327188 -0.019776516 0.995317459
1403638615727829504 -5.950421333 -1.224934220 1.976945043 0.038173266 -0.079510346 -0.015277815 0.995985687
1403638615777829376 -5.892971516 -1.225066543 1.962345004 0.039065588 -0.072496697 -0.012266734 0.996527791
1403638615827829504 -5.828789711 -1.240088463 1.954665184 0.038150597 -0.067315347 -0.010599320 0.996945739
1403638615877829376 -5.766191006 -1.244015098 1.933292150 0.038285829 -0.062428094 -0.004953810 0.997302532
1403638615927829504 -5.712035179 -1.247299433 1.928233385 0.039603591 -0.055539627 -0.002095156 0.997668564
1403638615977829376 -5.643130302 -1.258008122 1.906444788 0.036728803 -0.049566586 0.001608040 0.998093963
1403638616027829504 -5.580212593 -1.259918690 1.885371566 0.037712056 -0.043001685 0.004316567 0.998353660
1403638616077829376 -5.526411533 -1.263042569 1.878345728 0.038073305 -0.035573058 0.005435385 0.998626769
1403638616127829504 -5.456566811 -1.263583422 1.874910116 0.038339987 -0.029517096 0.007185495 0.998802841
1403638616177829376 -5.395977020 -1.259215236 1.855181694 0.037380964 -0.020949328 0.011372944 0.999016762
1403638616227829504 -5.342214108 -1.258460760 1.844912052 0.036231712 -0.011096759 0.014908865 0.999170601
1403638616277829376 -5.269890785 -1.233195901 1.834613085 0.037711773 -0.002057886 0.020068269 0.999085009
1403638616327829504 -5.222250462 -1.229361534 1.825715542 0.035302516 0.009737880 0.023913724 0.999043047
1403638616377829376 -5.157999992 -1.213104963 1.815320015 0.034652833 0.020204924 0.028249016 0.998795748
1403638616427829504 -5.100686073 -1.193230987 1.815595984 0.034103349 0.030744204 0.032249730 0.998424590
1403638616477829376 -5.037965775 -1.173409581 1.810204625 0.033393551 0.038894761 0.037209917 0.997991741
1403638616527829504 -4.980441093 -1.148948789 1.806158304 0.032142647 0.047152601 0.040044513 0.997566998
1403638616577829376 -4.911324024 -1.130364180 1.804758310 0.029955108 0.053713199 0.042158384 0.997216225
1403638616627829504 -4.856138706 -1.100015402 1.791069269 0.026520571 0.059203468 0.045232866 0.996867895
1403638616677829376 -4.795856953 -1.075564027 1.787813902 0.021043273 0.063454457 0.048006535 0.996607304
1403638616727829504 -4.736957550 -1.047047377 1.785929799 0.013469109 0.065455809 0.053010710 0.996355355
1403638616777829376 -4.677963734 -1.022109270 1.781904459 0.005567311 0.066105276 0.058437873 0.996084392
1403638616827829504 -4.618018150 -0.994937360 1.778333902 -0.000571373 0.066225477 0.063122638 0.995805919
1403638616877829376 -4.561168671 -0.971258998 1.779024124 -0.005416350 0.066505842 0.066070199 0.995581388
1403638616927829504 -4.503983021 -0.948932469 1.782834053 -0.004753186 0.067907155 0.065515727 0.995526850
1403638616977829376 -4.432394505 -0.928839624 1.778983116 -0.001788737 0.069092587 0.060789753 0.995754778
1403638617027829504 -4.371714592 -0.911393762 1.779939890 0.001357870 0.070628248 0.057479735 0.995844305
1403638617077829376 -4.295914650 -0.894902706 1.782648921 0.005346810 0.070810981 0.053434432 0.996043146
1403638617127829504 -4.242827892 -0.885323405 1.786163688 0.008727591 0.073082574 0.047615815 0.996150374
1403638617177829376 -4.173283577 -0.879417241 1.787471771 0.010105570 0.072829798 0.044240773 0.996311367
1403638617227829504 -4.111255169 -0.871239245 1.788658142 0.008953613 0.072761841 0.040897854 0.996470213
1403638617277829376 -4.048211098 -0.869568288 1.791246176 0.005901243 0.071745351 0.039294105 0.996631205
1403638617327829504 -3.981389999 -0.863217771 1.793696046 0.003469896 0.070448004 0.038928989 0.996749520
1403638617377829376 -3.915886641 -0.862039924 1.796034455 -0.000877664 0.069559403 0.037198722 0.996883631
1403638617427829504 -3.850919485 -0.863055408 1.797456026 -0.003881649 0.068764813 0.035294555 0.997000813
1403638617477829376 -3.788513899 -0.867180943 1.801292658 -0.005671400 0.067521416 0.034623012 0.997100770
1403638617527829504 -3.712616205 -0.871238470 1.803534389 -0.006688384 0.065686107 0.032647956 0.997283697
1403638617577829376 -3.663683414 -0.884171128 1.813975692 -0.007010460 0.066017210 0.032098807 0.997277379
1403638617627829504 -3.596154213 -0.897968650 1.820135593 -0.006281138 0.065045670 0.030184159 0.997405887
1403638617677829376 -3.535906553 -0.912969410 1.824601173 -0.004665697 0.064574286 0.027928306 0.997511089
1403638617727829504 -3.472971201 -0.929768801 1.831271887 -0.002787136 0.064239033 0.025568137 0.997603059
1403638617777829376 -3.419557095 -0.954068184 1.838540673 -0.001868915 0.063687205 0.025602549 0.997639716
1403638617827829504 -3.359201908 -0.978209913 1.846326232 -0.003245077 0.063562758 0.022970602 0.997708142
1403638617877829376 -3.296593666 -0.997070193 1.859632730 -0.001653246 0.062584884 0.022185439 0.997791648
1403638617927829504 -3.238414764 -1.028562188 1.865451813 -0.001090906 0.061350651 0.022875916 0.997853518
1403638617977829376 -3.171090603 -1.052117348 1.878392696 0.000014505 0.059679300 0.022702308 0.997959435
1403638618027829504 -3.124733686 -1.076577663 1.892649531 -0.000024907 0.060039375 0.022529829 0.997941732
1403638618077829376 -3.070617676 -1.103620887 1.901682615 0.000406334 0.059263695 0.021631565 0.998007834
1403638618127829504 -3.014418364 -1.121567011 1.923424721 -0.000071595 0.058185644 0.022720857 0.998047233
1403638618177829376 -2.962814093 -1.147135973 1.933814764 0.000584404 0.057515904 0.022873249 0.998082340
1403638618227829504 -2.903465748 -1.174628139 1.952295423 -0.000208626 0.056734968 0.021605436 0.998155475
1403638618277829376 -2.851093531 -1.185396194 1.980712295 0.000597833 0.056761090 0.021672796 0.998152316
1403638618327829504 -2.797564268 -1.199136376 2.008349657 0.002327789 0.056751508 0.020670464 0.998171628
1403638618377829376 -2.746800900 -1.222366452 2.028802156 0.002142255 0.056175623 0.020696122 0.998204052
1403638618427829504 -2.693542004 -1.238272190 2.056696177 0.002633611 0.055917934 0.020280790 0.998225868
1403638618477829376 -2.644917011 -1.261343002 2.076551437 0.001694957 0.054984502 0.019686095 0.998291671
1403638618527829504 -2.593449116 -1.277446747 2.109704733 0.003563666 0.054860301 0.019561103 0.998296022
1403638618577829376 -2.546272993 -1.293002725 2.139376879 0.004161767 0.055979535 0.018486788 0.998252094
1403638618627829504 -2.495824814 -1.314153790 2.169951439 0.004007584 0.058220103 0.019452786 0.998106182
1403638618677829376 -2.445880175 -1.335282087 2.199511528 0.003809286 0.060635194 0.018818414 0.997975290
1403638618727829504 -2.397149801 -1.353420138 2.231930494 0.004392295 0.062703140 0.018978624 0.997842073
1403638618777829376 -2.350661039 -1.370356917 2.264450073 0.005716154 0.064589009 0.020132730 0.997692466
1403638618827829504 -2.306529760 -1.395952821 2.297642708 0.006914064 0.066045940 0.021119885 0.997569084
1403638618877829376 -2.259974718 -1.423725963 2.326122761 0.008569456 0.068780735 0.021209892 0.997369468
1403638618927829504 -2.220799923 -1.448656201 2.360711336 0.011092698 0.073209688 0.022721346 0.996995986
1403638618977829376 -2.182172060 -1.477035642 2.386283875 0.014999141 0.079275854 0.024183217 0.996446431
1403638619027829504 -2.134078503 -1.498456120 2.425535440 0.018404933 0.087048069 0.027230795 0.995661736
1403638619077829376 -2.094002485 -1.522567272 2.457543135 0.020021511 0.096959330 0.029244058 0.994657159
1403638619127829504 -2.049953461 -1.532918096 2.503761530 0.023167986 0.107748561 0.032419510 0.993379295
1403638619177829376 -2.003733873 -1.556406975 2.535423279 0.024015957 0.118532382 0.037257727 0.991960227
1403638619227829504 -1.970728397 -1.571956396 2.576851368 0.026034957 0.131255910 0.042549867 0.990092695
1403638619277829376 -1.932882547 -1.587106824 2.617276907 0.026533309 0.144322291 0.049189318 0.987951159
1403638619327829504 -1.888767123 -1.599211931 2.658514977 0.027412390 0.157911286 0.054608986 0.985560954
1403638619377829376 -1.856566906 -1.607632756 2.701220751 0.028726449 0.171118081 0.060205214 0.982989728
1403638619427829504 -1.820097685 -1.617618203 2.741263866 0.029949065 0.182033598 0.066081412 0.980612099
1403638619477829376 -1.783050895 -1.626289845 2.784594536 0.030743046 0.191676721 0.071757942 0.978348494
1403638619527829504 -1.749255180 -1.638054132 2.819490433 0.031952582 0.199259028 0.076619305 0.976424277
1403638619577829376 -1.712210417 -1.649306417 2.860490322 0.032410588 0.205686808 0.081259511 0.974699616
1403638619627829504 -1.679753542 -1.653376102 2.903082848 0.033345249 0.209901184 0.087930240 0.973189533
1403638619677829376 -1.646314144 -1.660236001 2.939858198 0.035379130 0.211624116 0.096764974 0.971905410
1403638619727829504 -1.619004250 -1.666269660 2.982990742 0.035580222 0.213818818 0.102985427 0.970777810
1403638619777829376 -1.590303659 -1.665615678 3.023774862 0.037814301 0.215628237 0.107963897 0.969751716
1403638619827829504 -1.551941395 -1.675280333 3.060524225 0.038528476 0.216940016 0.111825585 0.968993068
1403638619877829376 -1.518973351 -1.671177149 3.098442078 0.039902933 0.218667030 0.113397047 0.968366444
1403638619927829504 -1.484071255 -1.675816178 3.133649349 0.039883241 0.220077336 0.115222484 0.967832148
1403638619977829376 -1.446785212 -1.677877665 3.165963411 0.039782993 0.221619353 0.115802646 0.967415094
1403638620027829504 -1.414012671 -1.679053068 3.199265003 0.041126665 0.223218694 0.115469113 0.967030942
1403638620077829376 -1.371926069 -1.669983149 3.232034922 0.043984387 0.223974392 0.115224607 0.966759622
1403638620127829504 -1.340173960 -1.671405435 3.260901928 0.046057630 0.226015940 0.113153473 0.966432512
1403638620177829376 -1.291436315 -1.674769044 3.296081781 0.048673175 0.227304012 0.111614309 0.966181159
1403638620227829504 -1.261122346 -1.684216261 3.332838535 0.049264047 0.229011029 0.110918805 0.965828121
1403638620277829376 -1.225037336 -1.697785378 3.361099243 0.046693891 0.230229720 0.109356299 0.965844274
1403638620327829504 -1.176116586 -1.703865767 3.388131142 0.045455053 0.231061503 0.106285043 0.966047585
1403638620377829376 -1.137294888 -1.703583837 3.400772572 0.045149609 0.231065899 0.105642892 0.966131270
1403638620427829504 -1.095037103 -1.713289499 3.416424274 0.044488996 0.230801776 0.104436554 0.966356218
1403638620477829376 -1.062623620 -1.725257754 3.452883005 0.043041553 0.231462881 0.103062496 0.966411114
1403638620527829504 -1.023846626 -1.751559854 3.460754633 0.041425083 0.231168509 0.102037542 0.966660976
1403638620577829376 -0.984683871 -1.756287694 3.484694958 0.040365070 0.230711803 0.101246975 0.966898024
1403638620627829504 -0.942534208 -1.731366634 3.485150337 0.040769331 0.228751555 0.101679489 0.967301369
1403638620677829376 -0.912767768 -1.721388221 3.505669832 0.040315885 0.228287578 0.102794036 0.967312157
1403638620727829504 -0.869562507 -1.742165804 3.516123533 0.035701510 0.226392880 0.104683593 0.967736006
1403638620777829376 -0.840943575 -1.761898160 3.522279024 0.032361690 0.225310192 0.105929330 0.967970550
1403638620827829504 -0.852422953 -1.729178190 3.573585987 0.032280914 0.228824362 0.102486096 0.967519462
1403638620877829376 -0.791540742 -1.707868338 3.562546253 0.031614475 0.227575362 0.098327003 0.968267441
1403638620927829504 -0.752807021 -1.708198190 3.589443684 0.030835131 0.228161156 0.095001094 0.968486667
1403638620977829376 -0.722926855 -1.712119222 3.609388351 0.030248392 0.229575530 0.090743318 0.968579233
1403638621027829504 -0.652826309 -1.743998766 3.596748829 0.030420946 0.227487773 0.089686170 0.969164729
1403638621077829376 -0.609553218 -1.741316676 3.603855610 0.031615600 0.227129057 0.086595744 0.969491601
1403638621127829504 -0.572157621 -1.761585116 3.632652760 0.031609163 0.227277234 0.086739607 0.969444275
1403638621177829376 -0.548249364 -1.733429193 3.642600536 0.035323154 0.226714879 0.084740758 0.969624519
1403638621227829504 -0.506627321 -1.730891943 3.655783415 0.037459079 0.226220354 0.083725028 0.969748080
1403638621277829376 -0.493720770 -1.736208797 3.662211418 0.038014926 0.227483466 0.082200132 0.969561398
1403638621327829504 -0.439284444 -1.731476188 3.678029060 0.037771020 0.226635322 0.080305755 0.969928205
1403638621377829376 -0.401655793 -1.765973210 3.688025713 0.035302822 0.226213157 0.079316296 0.970201135
1403638621427829504 -0.386021018 -1.755565882 3.694600582 0.038906038 0.226836950 0.078839764 0.969956517
1403638621477829376 -0.341331363 -1.767984271 3.707726479 0.039057162 0.226945952 0.076989725 0.970073521
1403638621527829504 -0.312936187 -1.769820333 3.721282721 0.041906737 0.226195261 0.075777836 0.970225394
1403638621577829376 -0.296451211 -1.780497551 3.731666088 0.042536225 0.227233887 0.074935615 0.970020652
1403638621627829504 -0.230718493 -1.775803328 3.735820532 0.044148684 0.224697724 0.075462610 0.970498443
1403638621677829376 -0.182120800 -1.784377217 3.743410110 0.043245301 0.223721236 0.075458638 0.970764995
1403638621727829504 -0.161331296 -1.764555931 3.740592718 0.045867521 0.223889381 0.074392833 0.970688164
1403638621777829376 -0.113331199 -1.753244162 3.763113499 0.047258865 0.222871408 0.073353253 0.970934749
1403638621827829504 -0.127225518 -1.739219904 3.790824890 0.050390817 0.226332679 0.070701785 0.970172942
1403638621877829376 -0.100838423 -1.723848224 3.802358627 0.054600257 0.226940006 0.069739275 0.969872952
1403638621927829504 -0.071356416 -1.740963221 3.810465336 0.054763287 0.226858556 0.069277279 0.969915926
1403638621977829376 0.039708853 -1.748449206 3.766187668 0.054977957 0.220898375 0.071964897 0.971083105
1403638622027829504 0.057183862 -1.729404330 3.785019875 0.056135949 0.221008986 0.071407467 0.971032858
1403638622077829376 0.069495201 -1.708902836 3.796501160 0.056846753 0.221493602 0.072294839 0.970815361
1403638622127829504 0.115919471 -1.685840726 3.787737846 0.056720108 0.218991369 0.074923411 0.971191049
1403638622177829376 0.141827941 -1.680614471 3.789724112 0.055050880 0.217876881 0.076391220 0.971423388
1403638622227829504 0.158480525 -1.674121499 3.796345711 0.054496493 0.218117267 0.077336900 0.971325874
1403638622277829376 0.145737648 -1.647727132 3.808454037 0.056840558 0.219383895 0.078876860 0.970782340
1403638622327829504 0.167286634 -1.641044259 3.803577423 0.055628084 0.219369724 0.080037870 0.970760703
1403638622377829376 0.208146334 -1.645473361 3.787445545 0.053498201 0.218744904 0.080306411 0.970999241
1403638622427829504 0.145850420 -1.629518867 3.831915140 0.053368703 0.225440040 0.077150196 0.969730079
1403638622477829376 0.231901646 -1.625711083 3.785983562 0.052025381 0.222012326 0.076594532 0.970637500
1403638622527829504 0.187591314 -1.608630419 3.806894302 0.053604208 0.226129293 0.074598178 0.969756305
1403638622577829376 0.190492392 -1.592207193 3.795676708 0.054126244 0.228579924 0.071424693 0.969391584
1403638622627829504 0.266545415 -1.618799686 3.747667789 0.054092735 0.225882113 0.071370535 0.970029652
1403638622677829376 0.265116096 -1.648607850 3.742076635 0.055505246 0.227629706 0.071227938 0.969551682
1403638622727829504 0.273629308 -1.662391424 3.718945503 0.063499361 0.228878483 0.069096692 0.968921125
1403638622777829376 0.276786447 -1.610021114 3.710771561 0.076556586 0.230019912 0.066227436 0.967906952
1403638622827829504 0.237333298 -1.619459867 3.693093777 0.082723588 0.234174296 0.064788841 0.966499686
1403638622877829376 0.280918956 -1.600930929 3.666205645 0.085074767 0.232116848 0.064497061 0.966811359
1403638622927829504 0.286861300 -1.603628159 3.640341997 0.083296075 0.231970012 0.066291906 0.966880083
1403638622977829376 0.289504409 -1.608853221 3.614535332 0.077892303 0.231784746 0.067738526 0.967274547
1403638623027829504 0.262327313 -1.619475245 3.586367130 0.071748093 0.232616708 0.070052721 0.967385292
1403638623077829376 0.259626269 -1.601021290 3.560887098 0.067376345 0.232359812 0.072056979 0.967614174
1403638623127829504 0.262062073 -1.602158308 3.522918463 0.062862732 0.231018901 0.076187022 0.967922568
1403638623177829376 0.258799911 -1.606820583 3.487674713 0.059208211 0.229821205 0.079018265 0.968211114
1403638623227829504 0.251403570 -1.585067153 3.459226131 0.057677187 0.229582295 0.080622315 0.968227983
1403638623277829376 0.264098167 -1.571644425 3.414727211 0.054248806 0.227638096 0.083035588 0.968681097
1403638623327829504 0.250686049 -1.568601608 3.388568640 0.050936393 0.228007182 0.083935648 0.968696535
1403638623377829376 0.265304089 -1.551016450 3.351552010 0.049116604 0.226013914 0.085832000 0.969091415
1403638623427829504 0.231964469 -1.542034984 3.322116375 0.045901876 0.228687584 0.083828218 0.968797088
1403638623477829376 0.235440612 -1.505721331 3.291084766 0.047272313 0.227667540 0.085220143 0.968850017
1403638623527829504 0.240756989 -1.496336937 3.253001213 0.045685202 0.226710334 0.085629664 0.969114482
1403638623577829376 0.255859375 -1.497982383 3.206928730 0.044518229 0.226196587 0.084102824 0.969422460
1403638623627829504 0.300833344 -1.492434621 3.163599730 0.043779045 0.223698884 0.083382674 0.970097661
1403638623677829376 0.241386175 -1.470795631 3.136452675 0.043419614 0.227476701 0.083698399 0.969207704
1403638623727829504 0.242857218 -1.442083240 3.091082096 0.044443920 0.227890238 0.082593746 0.969158947
1403638623777829376 0.214842677 -1.425338507 3.053942680 0.043232977 0.230049118 0.081813097 0.968769789
1403638623827829504 0.229493260 -1.390027165 3.010842800 0.044897217 0.229281142 0.079642005 0.969057024
1403638623877829376 0.232652783 -1.385483742 2.971638680 0.042031113 0.229401246 0.080885291 0.969054163
1403638623927829504 0.241023064 -1.362946153 2.922914267 0.042200871 0.229165480 0.080702975 0.969117761
1403638623977829376 0.207605362 -1.359518647 2.887418747 0.040533029 0.231521651 0.080045275 0.968683422
1403638624027829504 0.202606440 -1.345972180 2.845604181 0.040477838 0.231696397 0.080934189 0.968570054
1403638624077829376 0.203510284 -1.336447120 2.797879219 0.039520819 0.230963662 0.083649650 0.968553901
1403638624127829504 0.188591719 -1.325078964 2.752540112 0.039227009 0.231269121 0.085161142 0.968361199
1403638624177829376 0.168484092 -1.313086390 2.717728615 0.039404117 0.231694996 0.086554371 0.968128681
1403638624227829504 0.178539515 -1.299460173 2.670199871 0.038757395 0.230452582 0.088831872 0.968244970
1403638624277829376 0.169290662 -1.282416701 2.627397537 0.039291624 0.230304897 0.090115227 0.968140006
1403638624327829504 0.159232318 -1.270663977 2.590549231 0.039160855 0.230725005 0.091231331 0.967940688
1403638624377829376 0.146543384 -1.263843060 2.538788557 0.038430125 0.231178045 0.092161186 0.967773795
1403638624427829504 0.143097997 -1.239807367 2.505204916 0.038481738 0.231408775 0.092365630 0.967697144
1403638624477829376 0.136642694 -1.214120984 2.460368872 0.038729046 0.232266441 0.091619134 0.967552722
1403638624527829504 0.130072176 -1.184955239 2.424891710 0.044082738 0.231757998 0.094996251 0.967119813
1403638624577829376 0.124426305 -1.174056530 2.377265215 0.051957022 0.231056690 0.097512856 0.966646016
1403638624627829504 0.154593468 -1.152595162 2.327825785 0.058666911 0.229012549 0.098392799 0.966659367
1403638624677829376 0.128968477 -1.131665230 2.295787811 0.058797620 0.230174735 0.095345706 0.966680706
1403638624727829504 0.120856583 -1.093368292 2.248342037 0.056012318 0.229774401 0.089873530 0.967465281
1403638624777829376 0.100288808 -1.052001357 2.211885929 0.052133266 0.229298651 0.084106825 0.968313098
1403638624827829504 0.086176991 -1.034927845 2.165012836 0.046652019 0.227908835 0.079953484 0.969272196
1403638624877829376 0.067174315 -1.022709727 2.122128010 0.042451747 0.226654619 0.077379890 0.969967961
1403638624927829504 0.061530650 -0.997688890 2.067920208 0.040679105 0.222868964 0.077686079 0.970896244
1403638624977829376 0.038168609 -0.988107979 2.020705700 0.039015096 0.219916135 0.079172835 0.971517563
1403638625027829504 0.037187815 -0.973106205 1.966947913 0.038952298 0.216168419 0.080549359 0.972247779
1403638625077829376 0.017774403 -0.944109321 1.922479153 0.039309260 0.213056564 0.083087564 0.972706616
1403638625127829504 0.005421996 -0.925125003 1.871510983 0.039277501 0.210234210 0.085527062 0.973110437
1403638625177829376 -0.004168928 -0.903490186 1.825373769 0.038900495 0.207949802 0.086841226 0.973499954
1403638625227829504 -0.019401789 -0.883221269 1.776506066 0.038397506 0.206664994 0.086933963 0.973785222
1403638625277829376 -0.038360476 -0.863458514 1.726674438 0.038006138 0.206157461 0.086098477 0.973982394
1403638625327829504 -0.037382424 -0.835044920 1.679937363 0.038358815 0.204658940 0.086631812 0.974237263
1403638625377829376 -0.050112665 -0.810601354 1.634007573 0.038564216 0.204218686 0.086517848 0.974331677
1403638625427829504 -0.056187034 -0.792810380 1.581776619 0.038879987 0.203640163 0.086106457 0.974476635
1403638625477829376 -0.065052152 -0.779930890 1.538866758 0.039152320 0.203164816 0.086591221 0.974521995
1403638625527829504 -0.070462525 -0.761905074 1.485038280 0.038973797 0.203229100 0.085701019 0.974594414
1403638625577829376 -0.077914953 -0.739658773 1.430107355 0.038551148 0.203069821 0.085967720 0.974620998
1403638625627829504 -0.084470749 -0.722156942 1.375096321 0.036812909 0.203275695 0.085193597 0.974713206
1403638625677829376 -0.092874736 -0.709879398 1.327612638 0.035730246 0.203033760 0.085754670 0.974754751
1403638625727829504 -0.098774433 -0.701078773 1.270087957 0.031305157 0.202588677 0.086666673 0.974918842
1403638625777829376 -0.115913033 -0.682684839 1.225304365 0.027874107 0.202924564 0.087335803 0.974893391
1403638625827829504 -0.121558785 -0.662800670 1.171792030 0.024422605 0.202905476 0.088069968 0.974923909
1403638625877829376 -0.128021210 -0.648664832 1.119242907 0.023323318 0.203211203 0.087933056 0.974899471
1403638625927829504 -0.133171678 -0.636667252 1.070669174 0.022123333 0.203727886 0.087330483 0.974873781
1403638625977829376 -0.139471382 -0.616002440 1.022418022 0.022247527 0.204149947 0.087237701 0.974790990
1403638626027829504 -0.144080728 -0.598613262 0.969415128 0.020639477 0.204140887 0.088255748 0.974736631
1403638626077829376 -0.146428972 -0.582913160 0.929155529 0.019634714 0.203660071 0.089583442 0.974736810
1403638626127829504 -0.150293231 -0.553517103 0.884250283 0.019947281 0.203556702 0.090370886 0.974679351
1403638626177829376 -0.156073868 -0.541619360 0.836647391 0.018586731 0.204078913 0.089591235 0.974669039
1403638626227829504 -0.147720039 -0.510780990 0.795090497 0.019953787 0.204189748 0.089185476 0.974656045
1403638626277829376 -0.151610553 -0.489627063 0.748658180 0.021504451 0.205463678 0.086962745 0.974556148
1403638626327829504 -0.155055404 -0.465921015 0.712136567 0.022959879 0.207478330 0.082511254 0.974483192
1403638626377829376 -0.152846366 -0.456063002 0.674607992 0.023811592 0.209101871 0.078457206 0.974450529
1403638626427829504 -0.147681728 -0.417549253 0.627262235 0.026535423 0.209372878 0.076098837 0.974509001
1403638626477829376 -0.150045022 -0.394714266 0.592909992 0.026485261 0.209696367 0.075513802 0.974486351
1403638626527829504 -0.158937439 -0.380253911 0.569179058 0.023534859 0.210291803 0.074244529 0.974531293
1403638626577829376 -0.166284516 -0.361216009 0.533649743 0.021723650 0.210424140 0.074011773 0.974562466
1403638626627829504 -0.165467575 -0.330640107 0.492594123 0.020192731 0.209719494 0.075750649 0.974613667
1403638626677829376 -0.162122503 -0.305352867 0.439256400 0.018481979 0.209080592 0.075267628 0.974822283
1403638626727829504 -0.160059243 -0.272966504 0.401357263 0.015516644 0.207888097 0.077200294 0.974977911
1403638626777829376 -0.161111325 -0.254248857 0.368140340 0.012254698 0.207204282 0.078753002 0.975045741
1403638626827829504 -0.174766064 -0.242824644 0.335759550 0.009601396 0.207233250 0.079077862 0.975042999
1403638626877829376 -0.176536947 -0.224180356 0.311244339 0.007549754 0.207021311 0.078557730 0.975148141
1403638626927829504 -0.190239727 -0.214412823 0.289689332 0.005636640 0.207634881 0.078680985 0.975020647
1403638626977829376 -0.180885255 -0.208428696 0.250492513 0.005459533 0.206470877 0.079151548 0.975230753
1403638627027829504 -0.182377160 -0.196029782 0.203255057 0.005292551 0.206184700 0.079035357 0.975301623
1403638627077829376 -0.184783131 -0.177340984 0.190578714 0.005841399 0.205707014 0.079063013 0.975397110
1403638627127829504 -0.188235581 -0.167324528 0.163329065 0.005927800 0.205668122 0.078956887 0.975413382
1403638627177829376 -0.188654646 -0.149551377 0.138067424 0.006092314 0.205348402 0.079584286 0.975428760
1403638627227829504 -0.193938360 -0.140887544 0.118043557 0.006211804 0.205403924 0.079494514 0.975423634
1403638627277829376 -0.191350341 -0.117331624 0.090076618 0.006383522 0.205745146 0.077630609 0.975500703
1403638627327829504 -0.191742837 -0.105128184 0.068071619 0.006698379 0.206252217 0.076179117 0.975505948
1403638627377829376 -0.191155046 -0.091820665 0.047686990 0.007387234 0.206401467 0.075112410 0.975552142
1403638627427829504 -0.191061407 -0.073601171 0.028894357 0.007083431 0.206464306 0.074375540 0.975597560
1403638627477829376 -0.190933406 -0.060698818 0.010071427 0.006818982 0.206407815 0.074573413 0.975596309
1403638627527829504 -0.189827636 -0.047462754 -0.008073419 0.007463293 0.206285104 0.074997924 0.975584984
1403638627577829376 -0.190360159 -0.032408357 -0.022058561 0.008770700 0.207205161 0.073575586 0.975487411
1403638627627829504 -0.192281082 -0.018316017 -0.036510460 0.010900749 0.208278865 0.071711168 0.975376129
1403638627677829376 -0.191866428 -0.005858098 -0.051565468 0.013753809 0.208556741 0.071406648 0.975303054
1403638627727829504 -0.192685261 0.007560368 -0.062880307 0.016023565 0.209083438 0.070715912 0.975205958
1403638627777829376 -0.192548931 0.021206798 -0.073855460 0.016856782 0.209611788 0.069586180 0.975159764
1403638627827829504 -0.193348214 0.032956276 -0.086792961 0.018224709 0.209900066 0.069841638 0.975054860
1403638627877829376 -0.192268386 0.049647436 -0.094430551 0.017930578 0.210285038 0.068970740 0.975039303
1403638627927829504 -0.197994232 0.059911251 -0.106907040 0.015889317 0.210538596 0.069459535 0.974985301
1403638627977829376 -0.201191381 0.073513903 -0.115048498 0.014107211 0.210723564 0.069029227 0.975003362
1403638628027829504 -0.209395587 0.081097148 -0.122747548 0.012407704 0.211783126 0.068432771 0.974838912
1403638628077829376 -0.207087666 0.092083290 -0.133497983 0.011922889 0.211709350 0.068747379 0.974838853
1403638628127829504 -0.209659323 0.101218373 -0.139521271 0.010494717 0.212216005 0.068742819 0.974745452
1403638628177829376 -0.213720888 0.110497475 -0.146889895 0.010234248 0.212756887 0.068401799 0.974654257
1403638628227829504 -0.216573238 0.119128101 -0.152045503 0.010173151 0.212707847 0.069363981 0.974597573
1403638628277829376 -0.221046150 0.127085134 -0.156994641 0.009704482 0.213139340 0.069071360 0.974528909
1403638628327829504 -0.225801110 0.133949012 -0.160227075 0.008797175 0.213058442 0.070284136 0.974468470
1403638628377829376 -0.230301380 0.139494911 -0.164286137 0.008770103 0.212986678 0.070703395 0.974454105
1403638628427829504 -0.235162914 0.143416494 -0.167511582 0.009636831 0.211993769 0.073424563 0.974461198
1403638628477829376 -0.240751684 0.146349832 -0.169897646 0.014037549 0.210792959 0.078461923 0.974275649
1403638628527829504 -0.245880306 0.147416472 -0.171610638 0.020296317 0.209082022 0.083126962 0.974147141
1403638628577829376 -0.250924587 0.148281306 -0.174388021 0.026750853 0.207576707 0.086747684 0.973997533
1403638628627829504 -0.255231678 0.148168117 -0.176142246 0.032094818 0.206790313 0.090056002 0.973703027
1403638628677829376 -0.260345578 0.148766756 -0.180597395 0.033708420 0.205240980 0.093713991 0.973631084
1403638628727829504 -0.263115942 0.151607618 -0.182481825 0.033304829 0.205361947 0.092937395 0.973693967
1403638628777829376 -0.265824854 0.155641139 -0.185139537 0.031888302 0.206346527 0.091280058 0.973689973
1403638628827829504 -0.268365681 0.160652965 -0.187780857 0.030629382 0.207371846 0.089563482 0.973671973
1403638628877829376 -0.269860089 0.167786628 -0.189243853 0.030962922 0.208414689 0.086834192 0.973685980
1403638628927829504 -0.271004498 0.174652860 -0.191324860 0.030239595 0.209415659 0.084480189 0.973701060
1403638628977829376 -0.272519588 0.181964889 -0.192832038 0.029219108 0.210878104 0.081815861 0.973644078
1403638629027829504 -0.274738461 0.183460951 -0.201013073 0.027947035 0.211677253 0.079316057 0.973714888
1403638629077829376 -0.274944186 0.194553271 -0.198302001 0.027045690 0.212741315 0.076070406 0.973767400
1403638629127829504 -0.276744366 0.199449897 -0.201582879 0.025948873 0.213015363 0.075112700 0.973811686
1403638629177829376 -0.273429662 0.203961462 -0.204771176 0.025000459 0.213150322 0.073788904 0.973908186
1403638629227829504 -0.280690283 0.207631320 -0.207947180 0.024127873 0.213421121 0.073277071 0.973909497
1403638629277829376 -0.283095598 0.210139900 -0.210662454 0.024085207 0.213557735 0.072719380 0.973922431
1403638629327829504 -0.285965115 0.212682173 -0.214226604 0.022301588 0.213855058 0.072058938 0.973948777
1403638629377829376 -0.289460361 0.215141505 -0.216564238 0.018738778 0.213915944 0.072307326 0.973992050
1403638629427829504 -0.293337822 0.216793969 -0.219271794 0.015141594 0.213779122 0.073133968 0.974022925
1403638629477829376 -0.297667503 0.217953160 -0.221681386 0.010664829 0.213615775 0.074796252 0.973991871
1403638629527829504 -0.302316546 0.218631774 -0.222848415 0.006756273 0.212650687 0.077044420 0.974062681
1403638629577829376 -0.306505561 0.218206286 -0.223126009 0.005174939 0.212080255 0.078713633 0.974063277
1403638629627829504 -0.310922414 0.216573849 -0.221878111 0.006397390 0.209950194 0.085708901 0.973927081
1403638629677829376 -0.315003693 0.213725939 -0.221129835 0.009221027 0.207801819 0.092337228 0.973759294
1403638629727829504 -0.318078160 0.210610986 -0.219177246 0.013644059 0.206089407 0.097240046 0.973594069
1403638629777829376 -0.319625318 0.207220331 -0.216737047 0.018969454 0.205546662 0.100120522 0.973327577
1403638629827829504 -0.320239156 0.205183595 -0.213839591 0.024343453 0.204756558 0.102590665 0.973117292
1403638629877829376 -0.319917262 0.204317898 -0.209917426 0.029963721 0.205392674 0.101974070 0.972891212
1403638629927829504 -0.318281293 0.206603736 -0.205670699 0.034408923 0.207909599 0.096816704 0.972736418
1403638629977829376 -0.316095710 0.211107805 -0.200720966 0.039319996 0.210643306 0.090349711 0.972584307
1403638630027829504 -0.313786477 0.218135849 -0.195824683 0.044078950 0.213091746 0.084185757 0.972400010
1403638630077829376 -0.311319530 0.228046387 -0.189568028 0.045024045 0.215123370 0.079612195 0.972294569
1403638630127829504 -0.310422063 0.239870563 -0.185179383 0.043148484 0.216067895 0.076747745 0.972400427
1403638630177829376 -0.308046997 0.255070060 -0.177773654 0.040211618 0.216346353 0.074499570 0.972639263
1403638630227829504 -0.307346761 0.270415634 -0.173677713 0.036211170 0.216403678 0.074097760 0.972814322
1403638630277829376 -0.307247072 0.289407969 -0.167723417 0.032699261 0.216378167 0.073761910 0.972969890
1403638630327829504 -0.319719791 0.307087928 -0.174412087 0.027873948 0.216161653 0.077949382 0.972841740
1403638630377829376 -0.312608421 0.313545257 -0.148723498 0.002636578 0.211236283 0.083201632 0.973883867
1403638630427829504 -0.310330451 0.317546755 -0.082819216 0.019037815 0.208582222 0.091524974 0.973526657
1403638630477829376 -0.276025236 0.338740319 -0.025025576 0.037420128 0.211046726 0.083130457 0.973215461
1403638630527829504 -0.270031869 0.334142238 -0.036946431 0.039269540 0.210818589 0.083077580 0.973196566
1403638630577829376 -0.283308536 0.322332799 -0.033169463 0.038131524 0.211203009 0.083293192 0.973140001
1403638630627829504 -0.289655626 0.320117980 -0.024496630 0.037151266 0.212160438 0.080271557 0.973223627
1403638630677829376 -0.207779139 0.356459796 0.058856905 0.008779660 0.204135239 0.084537946 0.975246131
1403638630727829504 -0.168296173 0.304860443 -0.056402005 -0.007899249 0.195717692 0.081493326 0.977236390
1403638630777829376 -0.237467200 0.318591505 -0.124574587 -0.010090134 0.203486800 0.071906686 0.976381421
1403638630827829504 -0.297519028 0.332948148 -0.192245811 -0.006821171 0.204232186 0.074979365 0.976022959
1403638630877829376 -0.320068449 0.328579456 -0.218089074 -0.008934448 0.202597961 0.074308783 0.976397693
1403638630927829504 -0.339079052 0.329549313 -0.245940104 -0.009032297 0.203303739 0.073802486 0.976288438
1403638630977829376 -0.332217693 0.324545860 -0.227870345 -0.009205407 0.203178599 0.074531287 0.976257563
1403638631027829504 -0.332360208 0.324762911 -0.228068590 -0.008974490 0.202874392 0.074840024 0.976299345
1403638631077829376 -0.332120121 0.324704230 -0.228245348 -0.009413145 0.203045025 0.073520027 0.976360023
1403638631127829504 -0.332466722 0.324560881 -0.228149250 -0.009366454 0.202679813 0.075018048 0.976322412
1403638631177829376 -0.332146168 0.324710727 -0.228162915 -0.009319045 0.203187063 0.073796831 0.976310492
1403638631227829504 -0.332380295 0.324605703 -0.228013098 -0.009415206 0.202799141 0.074639134 0.976326168
1403638631277829376 -0.332217097 0.324848384 -0.228238910 -0.009537088 0.203135863 0.073466800 0.976343930
1403638631327829504 -0.332251012 0.324637651 -0.228151128 -0.008970793 0.202683672 0.074820511 0.976340473
1403638631377829376 -0.332180262 0.324964643 -0.227898121 -0.009521357 0.203226268 0.073650964 0.976311386
1403638631427829504 -0.332262903 0.324577659 -0.228275508 -0.009284987 0.202742055 0.074539073 0.976346910
1403638631477829376 -0.332217813 0.324777365 -0.228078201 -0.009344687 0.202824131 0.074343510 0.976344228
1403638631527829504 -0.332198709 0.324807763 -0.228051424 -0.009118264 0.202841535 0.074493051 0.976331353
1403638631577829376 -0.332246780 0.324909717 -0.228000134 -0.009119760 0.202753037 0.074270777 0.976366639
1403638631627829504 -0.332189232 0.324952602 -0.228182241 -0.009252615 0.202868670 0.074038401 0.976359010
1403638631677829376 -0.332222044 0.324725240 -0.228018999 -0.009193101 0.202762365 0.074772269 0.976325750
================================================
FILE: Examples/Stereo/kaist_vio_dataset.yaml
================================================
%YAML:1.0
#--------------------------------------------------------------------------------------------
# GPU Parameters
#--------------------------------------------------------------------------------------------
gpu.use_gpu: 1
gpu.is_jetson: 0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
#1280x720
#Camera.fx: 735
#Camera.fy: 735
#Camera.cx: 679
#Camera.cy: 288
#640x480
Camera.fx: 380.9
Camera.fy: 380.2
Camera.cx: 324.6
Camera.cy: 224.6
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
#Camera.k1: 0.006896928127777268
#Camera.k2: -0.009144207062654397
#Camera.p1: 0.000254113977103925
#Camera.p2: 0.0021434982252719545
#k1: 0.007044055287844759
#k2: -0.010251485722185347
#p1: 0.0006674304399871926
#p2: 0.001678899816379666
#Camera.width: 1280
#Camera.height: 720
Camera.width: 640
Camera.height: 480
#Camera.width: 320
#Camera.height: 240
# Camera frames per second
Camera.fps: 40
# stereo baseline times fx
#Camera.bf: 58.76
#Camera.bf: 50.63
Camera.bf: 19
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
ORBextractor.tile_h: 20
ORBextractor.tile_w: 20
ORBextractor.fixed_multi_scale_tile_size: 0
ORBextractor.apply_nms_ms: 1
ORBextractor.nms_ms_mode_gpu: 1
ORBextractor.scaleFactor: 1.2
ORBextractor.nLevels: 4
# ORB Extractor: Fast threshold
# Firstly we impose th_FAST_MAX. If no corners are detected we impose a lower value th_FAST_MIN
# You can lower these values if your images have low contrast
ORBextractor.th_FAST_MIN: 7
ORBextractor.th_FAST_MAX: 20
ORBextractor.FAST_N_MIN: 9
ORBextractor.FAST_N_MAX: 14
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.6
Viewer.KeyFrameLineWidth: 2
Viewer.GraphLineWidth: 1
Viewer.PointSize:2
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -100
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
================================================
FILE: Examples/Stereo/stereo_euroc.cpp
================================================
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
vector &vstrImageLeft, vector &vstrImageRight, vector &vTimeStamps);
int main(int argc, char **argv)
{
if(argc != 6)
{
cerr << endl << "Usage: ./stereo_euroc path_to_vocabulary path_to_settings path_to_left_folder path_to_right_folder path_to_times_file" << endl;
return 1;
}
std::string str_vocab = argv[1];
std::string str_settings = argv[2];
std::string str_left = argv[3];
std::string str_right = argv[4];
std::string str_time = argv[5];
// Retrieve paths to images
vector vstrImageLeft;
vector vstrImageRight;
vector vTimeStamp;
LoadImages(str_left, str_right, str_time, vstrImageLeft, vstrImageRight, vTimeStamp);
if(vstrImageLeft.empty() || vstrImageRight.empty())
{
cerr << "ERROR: No images in provided path." << endl;
return 1;
}
if(vstrImageLeft.size()!=vstrImageRight.size())
{
cerr << "ERROR: Different number of left and right images." << endl;
return 1;
}
// Read rectification parameters
cv::FileStorage fsSettings(str_settings, cv::FileStorage::READ);
if(!fsSettings.isOpened())
{
cerr << "ERROR: Wrong path to settings" << endl;
return -1;
}
cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r;
fsSettings["LEFT.K"] >> K_l;
fsSettings["RIGHT.K"] >> K_r;
fsSettings["LEFT.P"] >> P_l;
fsSettings["RIGHT.P"] >> P_r;
fsSettings["LEFT.R"] >> R_l;
fsSettings["RIGHT.R"] >> R_r;
fsSettings["LEFT.D"] >> D_l;
fsSettings["RIGHT.D"] >> D_r;
int rows_l = fsSettings["LEFT.height"];
int cols_l = fsSettings["LEFT.width"];
int rows_r = fsSettings["RIGHT.height"];
int cols_r = fsSettings["RIGHT.width"];
if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() ||
rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0)
{
cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl;
return -1;
}
cv::Mat M1l,M2l,M1r,M2r;
cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,M1l,M2l);
cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,M1r,M2r);
const int nImages = vstrImageLeft.size();
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(str_vocab,str_settings,Jetson_SLAM::System::STEREO,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
// Main loop
cv::Mat imLeft, imRight, imLeftRect, imRightRect;
for(int ni=0; ni >(t2 - t1).count();
vTimesTrack[ni]=ttrack;
// // Wait to load the next frame
// double T=0;
// if(ni0)
// T = tframe-vTimeStamp[ni-1];
// if(ttrack &vstrImageLeft, vector &vstrImageRight, vector &vTimeStamps)
{
ifstream fTimes;
fTimes.open(strPathTimes.c_str());
vTimeStamps.reserve(5000);
vstrImageLeft.reserve(5000);
vstrImageRight.reserve(5000);
while(!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
{
stringstream ss;
ss << s;
vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
double t;
ss >> t;
vTimeStamps.push_back(t);
}
}
}
================================================
FILE: Examples/Stereo/stereo_kitti.cpp
================================================
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
void LoadImages(const string &strPathToSequence, vector &vstrImageLeft,
vector &vstrImageRight, vector &vTimestamps);
void LoadImages_VO_seq(const string &strPathToSequence, vector &vstrImageLeft,
vector &vstrImageRight, vector &vTimestamps);
int main(int argc, char **argv)
{
if(argc != 4)
{
cerr << endl << "Usage: ./stereo_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
return 1;
}
std::string str_vocab = argv[1];
std::string str_settings = argv[2];
std::string str_seq_path = argv[3];
// Retrieve paths to images
vector vstrImageLeft;
vector vstrImageRight;
vector vTimestamps;
// LoadImages(string(str_seq_path), vstrImageLeft, vstrImageRight, vTimestamps);
LoadImages_VO_seq(string(str_seq_path), vstrImageLeft, vstrImageRight, vTimestamps);
int nImages = vstrImageLeft.size();
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(str_vocab, str_settings,Jetson_SLAM::System::STEREO,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
{cv::Mat im(200,200, CV_8UC1);
cv::imshow("he",im);
cv::waitKey(0);}
// Main loop
cv::Mat imLeft, imRight;
// nImages = 4;
for(int ni=0; ni >(t2 - t1).count();
vTimesTrack[ni]=ttrack;
// // Wait to load the next frame
// double T=0;
// if(ni0)
// T = tframe-vTimestamps[ni-1];
// if(ttrack &vstrImageLeft,
vector &vstrImageRight, vector &vTimestamps)
{
ifstream fTimes;
string strPathTimeFile = strPathToSequence + "/times.txt";
fTimes.open(strPathTimeFile.c_str());
while(!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t;
ss >> t;
vTimestamps.push_back(t);
}
}
string strPrefixLeft = strPathToSequence + "/image_0/";
string strPrefixRight = strPathToSequence + "/image_1/";
const int nTimes = vTimestamps.size();
vstrImageLeft.resize(nTimes);
vstrImageRight.resize(nTimes);
for(int i=0; i &vstrImageLeft,
vector &vstrImageRight, vector &vTimestamps)
{
ifstream fTimes;
string strPathTimeFile = strPathToSequence + "/timestamps.txt";
fTimes.open(strPathTimeFile.c_str());
while(!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t;
ss >> t;
vTimestamps.push_back(t);
}
}
string strPrefixLeft = strPathToSequence + "/image_00/data/";
string strPrefixRight = strPathToSequence + "/image_01/data/";
const int nTimes = vTimestamps.size();
vstrImageLeft.resize(nTimes);
vstrImageRight.resize(nTimes);
for(int i=0; i (University of Zaragoza)
* For more information see
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see .
*/
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
int main(int argc, char **argv)
{
if(argc != 3)
{
cerr << endl << "Usage: ./stereo_live path_to_vocabulary path_to_settings" << endl;
return 1;
}
// Retrieve paths to images
vector vstrImageLeft;
vector vstrImageRight;
vector vTimestamps;
int nImages = vstrImageLeft.size();
std::string str_vocab = argv[1];
std::string str_settings = argv[2];
// Create SLAM system. It initializes all system threads and gets ready to process frames.
Jetson_SLAM::System SLAM(str_vocab, str_settings, Jetson_SLAM::System::STEREO,true);
// Vector for tracking time statistics
vector vTimesTrack;
vTimesTrack.resize(nImages);
cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
// Main loop
cv::Mat imLeft, imRight;
cv::VideoCapture vcl(0);
cv::VideoCapture vcr(1);
int im_width = 320;
int im_height = 240;
int resize_width = 320;
int resize_height = 240;
vcl.set(CV_CAP_PROP_FRAME_HEIGHT, im_height);
vcl.set(CV_CAP_PROP_FRAME_WIDTH, im_width);
vcr.set(CV_CAP_PROP_FRAME_HEIGHT, im_height);
vcr.set(CV_CAP_PROP_FRAME_WIDTH, im_width);
float total_time = 0;
int count = 0;
while(1)
{
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
double ttrack;
t1 = std::chrono::steady_clock::now();
vcl >> imLeft;
vcr >> imRight;
double tframe = std::time(0);// vTimestamps[ni];
// Pass the images to the SLAM system
cv::Mat pose = SLAM.TrackStereo(imLeft,imRight,tframe);
if(!pose.empty())
std::cout << pose << "\n";
// double ttrack= std::chrono::duration_cast >(t2 - t1).count();
// std::cout << "Track time = " << ttrack << "\n";
if(count >=nImages)
break;
}
// Stop all threads
SLAM.Shutdown();
// // Tracking time statistics
// sort(vTimesTrack.begin(),vTimesTrack.end());
// float totaltime = 0;
// for(int ni=0; ni
# Main Highlight
# 1. Main Results
### Datasets
1. [KITTI-Benchmark](https://github.com/zinuok/VINS-MONO)
2. [EuRoC Benchmark](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets)
3. [KAIST-VIO Benchmark](https://github.com/url-kaist/kaistviodataset)
#### Results on KITTI Benchmark


#### Results on EuRoC Benchmark



#### Results on KAIST-VIO Benchmark


#### Performance with scaled versions of VGG-16 Co-existing on Jetson-NX

### Build Instructions
**Step-1**
Install the dependencies given below:
1. OpenCV 4 (Currently tested with 4.10.0)
2. Eigen3
3. CUDA
4. Pangolin
5. cmake 3.31
**Step-2**
Run build.sh
### Run Instructions
Go to execs and run Jetson-SLAM on following choices:
1. Run stereo_kitti for KITTI-Benchmark
2. Run stereo_euroc for EuRoC Benchmark
3. Run stereo_kaistvio for KAIST-VIO Benchmark
4. Run stereo_live for live images from a Stereo-Rig. Please customize the "stereo_live_config.yaml" file for your stereo rig.
### Image Masks
Jetson-SLAM expects one mask for monocular/RGBD while two masks for stereo configuration. There are two mask path for each left and right image in the yaml file. Only non-zero regions in the mask shall be used to detect and extract keypoints. These masks are helpful when the camera is mounted on a structure and some part of the structure is always present in the camera field of view. Manytimes, this leads to static keypoints on the structure visible in the camera which degrades SLAM's accuracy because these points never moves w.r.t. camera.
If such requirement is not needed, one can simply create a white image of size equal to the RGB/grayscale image size that would be supplied into Jetson-SLAM.
e.g. If your RGB/grayscale image size is 240x240, simply create a mask of size 240x240 and supply the path to the yaml file. IF you need to hide some regions of the image, you can choose linux tool such as "GIMP" or any software of your choice.
### License
Jetson-SLAM is released under a [GPLv3 license].
### Bibtex citation:
@article{kumar2023high,
title={High-speed stereo visual SLAM for low-powered computing devices},
author={Kumar, Ashish and Park, Jaesik and Behera, Laxmidhar},
journal={IEEE Robotics and Automation Letters},
year={2023},
publisher={IEEE}
}
================================================
FILE: Thirdparty/DBoW2/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8)
project(DBoW2)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
set(HDRS_DBOW2
DBoW2/BowVector.h
DBoW2/FORB.h
DBoW2/FClass.h
DBoW2/FeatureVector.h
DBoW2/ScoringObject.h
DBoW2/TemplatedVocabulary.h)
set(SRCS_DBOW2
DBoW2/BowVector.cpp
DBoW2/FORB.cpp
DBoW2/FeatureVector.cpp
DBoW2/ScoringObject.cpp)
set(HDRS_DUTILS
DUtils/Random.h
DUtils/Timestamp.h)
set(SRCS_DUTILS
DUtils/Random.cpp
DUtils/Timestamp.cpp)
find_package(OpenCV 4 REQUIRED)
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
include_directories(${OpenCV_INCLUDE_DIRS})
add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS})
target_link_libraries(DBoW2 ${OpenCV_LIBS})
================================================
FILE: Thirdparty/DBoW2/DBoW2/BowVector.cpp
================================================
/**
* File: BowVector.cpp
* Date: March 2011
* Author: Dorian Galvez-Lopez
* Description: bag of words vector
* License: see the LICENSE.txt file
*
*/
#include
#include
#include
#include
#include
#include "BowVector.h"
namespace DBoW2 {
// --------------------------------------------------------------------------
BowVector::BowVector(void)
{
}
// --------------------------------------------------------------------------
BowVector::~BowVector(void)
{
}
// --------------------------------------------------------------------------
void BowVector::addWeight(WordId id, WordValue v)
{
BowVector::iterator vit = this->lower_bound(id);
if(vit != this->end() && !(this->key_comp()(id, vit->first)))
{
vit->second += v;
}
else
{
this->insert(vit, BowVector::value_type(id, v));
}
}
// --------------------------------------------------------------------------
void BowVector::addIfNotExist(WordId id, WordValue v)
{
BowVector::iterator vit = this->lower_bound(id);
if(vit == this->end() || (this->key_comp()(id, vit->first)))
{
this->insert(vit, BowVector::value_type(id, v));
}
}
// --------------------------------------------------------------------------
void BowVector::normalize(LNorm norm_type)
{
double norm = 0.0;
BowVector::iterator it;
if(norm_type == DBoW2::L1)
{
for(it = begin(); it != end(); ++it)
norm += fabs(it->second);
}
else
{
for(it = begin(); it != end(); ++it)
norm += it->second * it->second;
norm = sqrt(norm);
}
if(norm > 0.0)
{
for(it = begin(); it != end(); ++it)
it->second /= norm;
}
}
// --------------------------------------------------------------------------
std::ostream& operator<< (std::ostream &out, const BowVector &v)
{
BowVector::const_iterator vit;
std::vector::const_iterator iit;
unsigned int i = 0;
const unsigned int N = v.size();
for(vit = v.begin(); vit != v.end(); ++vit, ++i)
{
out << "<" << vit->first << ", " << vit->second << ">";
if(i < N-1) out << ", ";
}
return out;
}
// --------------------------------------------------------------------------
void BowVector::saveM(const std::string &filename, size_t W) const
{
std::fstream f(filename.c_str(), std::ios::out);
WordId last = 0;
BowVector::const_iterator bit;
for(bit = this->begin(); bit != this->end(); ++bit)
{
for(; last < bit->first; ++last)
{
f << "0 ";
}
f << bit->second << " ";
last = bit->first + 1;
}
for(; last < (WordId)W; ++last)
f << "0 ";
f.close();
}
// --------------------------------------------------------------------------
} // namespace DBoW2
================================================
FILE: Thirdparty/DBoW2/DBoW2/BowVector.h
================================================
/**
* File: BowVector.h
* Date: March 2011
* Author: Dorian Galvez-Lopez
* Description: bag of words vector
* License: see the LICENSE.txt file
*
*/
#ifndef __D_T_BOW_VECTOR__
#define __D_T_BOW_VECTOR__
#include
#include