├── examples ├── CMakeLists.txt ├── icp.cpp └── robust_pgo_mc.cpp ├── CMakeLists.txt ├── .gitignore ├── README.md ├── include ├── PosePointFactor.h └── pgo_utils.h └── data └── pointclouds ├── bunny_sparse100_part1.xyz ├── bunny_sparse100_part2.xyz ├── dragon_sparse100_part1.xyz ├── dragon_sparse100_part2.xyz └── bunny_sparse10_part1.xyz /examples/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | add_executable(icp icp.cpp) 2 | target_link_libraries(icp dcsam gtsam) 3 | 4 | add_executable(robust_pgo_mc robust_pgo_mc.cpp) 5 | target_link_libraries(robust_pgo_mc dcsam gtsam) 6 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.15) 2 | project(dcsam_examples) 3 | 4 | # Set some compilation options. 5 | set(CMAKE_CXX_STANDARD 17) 6 | add_compile_options(-Wall -Wpedantic -Wextra) 7 | 8 | # External package dependencies. 9 | find_package(GTSAM 4.2 REQUIRED) 10 | find_package(Eigen3 3.3 REQUIRED) 11 | find_package(dcsam REQUIRED) 12 | 13 | include_directories(include) 14 | add_subdirectory(examples) 15 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # OS generated files # 2 | ###################### 3 | .DS_Store 4 | .DS_Store? 5 | ._* 6 | .Spotlight-V100 7 | .Trashes 8 | ehthumbs.db 9 | [Tt]humbs.db 10 | 11 | # Jupyter Notebooks # 12 | ##################### 13 | .ipynb_checkpoints 14 | 15 | # Binaries # 16 | ############ 17 | *.pyc 18 | 19 | # Latex # 20 | ######### 21 | *.aux 22 | *.fdb_latexmk 23 | *.fls 24 | *.log 25 | *.out 26 | *.synctex.gz 27 | *.bbl 28 | *.blg 29 | *.toc 30 | *.dvi 31 | *.lof 32 | *.lot 33 | main.pdf 34 | 35 | # spacemacs # 36 | ############# 37 | auto/ 38 | .#* 39 | 40 | # Python # 41 | ########## 42 | __pycache__/ 43 | 44 | 45 | # PyTorch # 46 | ########### 47 | *.pt 48 | 49 | # Executables/C++ # 50 | ################### 51 | build/ 52 | 53 | # Tensorflow # 54 | ############## 55 | *.tfrecord 56 | *.pb 57 | 58 | # Temporary Files # 59 | ################### 60 | *.*~ 61 | *.swp 62 | 63 | # Large Files # 64 | ############### 65 | *.png 66 | *.mp4 67 | *.jpg 68 | 69 | # Blender # 70 | ########### 71 | *.blend 72 | 73 | # MATLAB # 74 | ########## 75 | *.m~ 76 | 77 | # ROS # 78 | ####### 79 | *.bag 80 | 81 | # Jekyll # 82 | ########## 83 | .jekyll-metadata 84 | .sass-cache/ 85 | Gemfile.lock 86 | _site/ 87 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # dcsam-examples 2 | 3 | This repository contains example code for the experiments provided in 4 | our paper "[Discrete-Continuous Smoothing and Mapping](https://arxiv.org/abs/2204.11936)." 5 | 6 | **NOTE: As of 1/30/2023 the latest version of DC-SAM (and dcsam-examples) on `main` depends on GTSAM release 4.2a8.** If you are using GTSAM 4.1.1, check out our [pre-4.2 release tag](https://github.com/MarineRoboticsGroup/dcsam-examples/releases/tag/pre-4.2) and the [corresponding pre-4.2 version of DC-SAM](https://github.com/MarineRoboticsGroup/dcsam/releases/tag/pre-4.2). This is the version of DC-SAM (and dcsam-examples) you would have used if you cloned the repository prior to 1/30/2023. Many thanks to [Parker Lusk](https://github.com/plusk01) for bringing us into the future. 7 | 8 | The file `icp.cpp` implements the iterative closest point (ICP) method for point 9 | cloud registration. 10 | 11 | The file `robust_pgo_mc.cpp` implements robust pose-graph optimization by 12 | introducing inlier/outlier discrete hypotheses for untrusted loop closure edges. 13 | 14 | To build the ICP and robust PGO examples: 15 | 16 | ```bash 17 | ~ $ mkdir build 18 | ~ $ cd build 19 | ~/build $ cmake .. 20 | ~/build $ make -j 21 | ``` 22 | 23 | To run the ICP example: 24 | ```bash 25 | ~/build/examples $ ./icp (path to source cloud) (path to target cloud) 26 | ``` 27 | 28 | To run the robust pose-graph optimization example: 29 | ```bash 30 | ~/build/examples $ ./robust_pgo_mc [.g2o file] [outlier rate (int >= 0; default 0)] [is3D (0/1; default 1)] [num trials (default 1)] 31 | ``` 32 | -------------------------------------------------------------------------------- /include/PosePointFactor.h: -------------------------------------------------------------------------------- 1 | /** 2 | * PosePointFactor.h 3 | * A simple factor representing the cost: 4 | * f(T) : = ||Tp - q||^2 5 | * where p,q \in R^3 and T \in SE(3) 6 | */ 7 | #pragma once 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | class PosePointFactor : public gtsam::NonlinearFactor { 14 | private: 15 | gtsam::Point3 p_; 16 | gtsam::Point3 q_; 17 | 18 | public: 19 | PosePointFactor(const gtsam::Key &k, const gtsam::Point3 &p, 20 | const gtsam::Point3 &q) 21 | : p_(p), q_(q) { 22 | keys_.push_back(k); 23 | } 24 | 25 | gtsam::Vector error_vector(const gtsam::Values &values) const { 26 | gtsam::Pose3 T = values.at(keys_[0]); 27 | gtsam::Point3 transformed_p = T.transformFrom(p_); 28 | gtsam::Point3 delta = transformed_p - q_; 29 | return gtsam::Vector3(delta.x(), delta.y(), delta.z()); 30 | } 31 | 32 | double error(const gtsam::Values &values) const override { 33 | gtsam::Pose3 T = values.at(keys_[0]); 34 | gtsam::Point3 transformed_p = T.transformFrom(p_); 35 | gtsam::Point3 delta = transformed_p - q_; 36 | 37 | // Return the squared norm of the error. 38 | return pow(delta.norm(), 2); 39 | } 40 | 41 | size_t dim() const override { return 3; }; 42 | 43 | boost::shared_ptr linearize( 44 | const gtsam::Values &values) const override { 45 | gtsam::Pose3 T = values.at(keys_[0]); 46 | Eigen::Matrix H; 47 | gtsam::Point3 transformed_p = T.transformFrom(p_, &H); 48 | return boost::make_shared(keys_[0], H, 49 | -error_vector(values)); 50 | } 51 | }; 52 | -------------------------------------------------------------------------------- /examples/icp.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | #include "PosePointFactor.h" 10 | 11 | std::vector read_xyz_file(const std::string& path_to_file) { 12 | // Vector of points to output. 13 | std::vector points; 14 | 15 | // A string containing the elements of each line. 16 | std::string line; 17 | 18 | // Preallocate x, y, z coordinates for each point. 19 | double x, y, z; 20 | 21 | // Open file for reading. 22 | std::ifstream infile(path_to_file); 23 | 24 | size_t i = 0; 25 | while (std::getline(infile, line)) { 26 | // Construct a stream from line. 27 | std::stringstream strstrm(line); 28 | 29 | // Extract formatted point. 30 | strstrm >> x >> y >> z; 31 | 32 | // Convert x, y, z to gtsam::Point3. 33 | gtsam::Point3 point(x, y, z); 34 | 35 | points.push_back(point); 36 | } 37 | 38 | return points; 39 | } 40 | 41 | int main(int argc, char** argv) { 42 | if (argc != 3) { 43 | std::cout << "Usage: " << argv[0] << " [source .xyz file]" 44 | << " [target .xyz file]" << std::endl; 45 | exit(1); 46 | } 47 | 48 | // Read source and target point clouds 49 | std::vector source = read_xyz_file(argv[1]); 50 | std::vector target = read_xyz_file(argv[2]); 51 | 52 | std::cout << "Loaded " << source.size() 53 | << " points from source cloud in file " << argv[1] << " and \n" 54 | << target.size() << " points from target cloud in file " << argv[2] 55 | << std::endl; 56 | 57 | if (source.size() == 0 || target.size() == 0) { 58 | std::cout 59 | << "Error: no measurements found in one or more input pointclouds." 60 | << std::endl; 61 | exit(1); 62 | } 63 | 64 | std::cout << source[0].x() << ", " << source[0].y() << ", " << source[0].z() 65 | << std::endl; 66 | 67 | gtsam::KeyVector poseKey{gtsam::Symbol('x', 1)}; 68 | 69 | // Create factor graph 70 | dcsam::HybridFactorGraph hfg; 71 | for (size_t i = 0; i < source.size(); i++) { 72 | std::vector components; 73 | for (size_t j = 0; j < target.size(); j++) { 74 | components.push_back(PosePointFactor(poseKey[0], source[i], target[j])); 75 | } 76 | gtsam::DiscreteKey dk(gtsam::Symbol('d', i), target.size()); 77 | dcsam::DCMixtureFactor dcm(poseKey, dk, components, true); 78 | hfg.push_dc(dcm); 79 | } 80 | 81 | std::cout << "Built HybridFactorGraph with " << hfg.size() << " factors." 82 | << std::endl; 83 | 84 | // Create DCSAM instance. 85 | dcsam::DCSAM dcsam; 86 | gtsam::Values initial_values; 87 | // Currently DCSAM requires that we provide initial discrete values, but they 88 | // aren't actually used since we perform the discrete solve first, so we 89 | // just set them all to 0. 90 | dcsam::DiscreteValues initial_discrete; 91 | for (size_t i = 0; i < source.size(); i++) { 92 | initial_discrete[gtsam::Symbol('d', i)] = 0; 93 | } 94 | initial_values.insert(poseKey[0], gtsam::Pose3::Identity()); 95 | 96 | // Compute the first iterate. 97 | dcsam.update(hfg, initial_values, initial_discrete); 98 | dcsam::DCValues estimate = dcsam.calculateEstimate(); 99 | std::cout << "pose out: " << std::endl; 100 | estimate.continuous.at(poseKey[0]).print(); 101 | std::ofstream file1("out1.txt"); 102 | file1 << estimate.continuous.at(poseKey[0]).matrix(); 103 | 104 | // Perform a few more iterations, writing to file each time: 105 | dcsam.update(); 106 | estimate = dcsam.calculateEstimate(); 107 | std::cout << "pose out 2: " << std::endl; 108 | estimate.continuous.at(poseKey[0]).print(); 109 | std::ofstream file2("out2.txt"); 110 | file2 << estimate.continuous.at(poseKey[0]).matrix(); 111 | 112 | dcsam.update(); 113 | estimate = dcsam.calculateEstimate(); 114 | std::cout << "pose out 3: " << std::endl; 115 | estimate.continuous.at(poseKey[0]).print(); 116 | std::ofstream file3("out3.txt"); 117 | file3 << estimate.continuous.at(poseKey[0]).matrix(); 118 | 119 | dcsam.update(); 120 | estimate = dcsam.calculateEstimate(); 121 | std::cout << "pose out 4: " << std::endl; 122 | estimate.continuous.at(poseKey[0]).print(); 123 | std::ofstream file4("out4.txt"); 124 | file4 << estimate.continuous.at(poseKey[0]).matrix(); 125 | 126 | dcsam.update(); 127 | estimate = dcsam.calculateEstimate(); 128 | std::cout << "pose out 5: " << std::endl; 129 | estimate.continuous.at(poseKey[0]).print(); 130 | std::ofstream file5("out5.txt"); 131 | file5 << estimate.continuous.at(poseKey[0]).matrix(); 132 | } 133 | -------------------------------------------------------------------------------- /include/pgo_utils.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | #include 16 | #include 17 | 18 | // Generate incorrect loop closures 19 | 20 | /** 21 | * A factor is considered a loop closure if it is between two non-consecutive 22 | * poses. 23 | */ 24 | bool isLoopClosure(const gtsam::NonlinearFactor& factor) { 25 | // Convert key indices to int to avoid wraparound issues 26 | gtsam::KeyVector keys = factor.keys(); 27 | if (keys.size() != 2) { 28 | return false; 29 | } 30 | int i = static_cast(gtsam::Symbol(keys[0]).index()); 31 | int j = static_cast(gtsam::Symbol(keys[1]).index()); 32 | return (abs(i - j) > 1); 33 | } 34 | 35 | gtsam::NonlinearFactorGraph generateRandomLoopClosures( 36 | const gtsam::KeyVector& keys, size_t num, 37 | const gtsam::SharedNoiseModel& inlier_model, bool is3D = true, 38 | size_t random_seed = 7) { 39 | // Set up random generator for selecting indices 40 | // We fix the random seed at 7 (selected arbitrarily) so that results can be 41 | // reproduced in a deterministic manner, but any random seed will be fine :) 42 | std::mt19937 rng(random_seed); 43 | 44 | // Set up random generator for poses (translation + rotation) 45 | std::uniform_real_distribution t_distribution(-5.0, 5.0); 46 | std::uniform_real_distribution u_distribution(0.0, 1.0); 47 | std::uniform_real_distribution R_distribution(0.0, 6.28); 48 | 49 | gtsam::NonlinearFactorGraph graph; 50 | for (size_t k = 0; k < num; k++) { 51 | // Randomly select i 52 | std::uniform_int_distribution uniform(0, keys.size()); 53 | 54 | auto i = uniform(rng); 55 | 56 | // Randomly select j 57 | auto j = uniform(rng); 58 | 59 | // Ensure the edge (i,j) is a loop closure. 60 | while (abs(j - i) <= 1) { 61 | j = uniform(rng); 62 | } 63 | 64 | /// Generate the measurement 65 | // Translation part 66 | double dx = t_distribution(rng); 67 | double dy = t_distribution(rng); 68 | double dz = t_distribution(rng); 69 | 70 | // Quaternion random sampling http://planning.cs.uiuc.edu/node198.html 71 | double u1 = u_distribution(rng); 72 | double u2 = u_distribution(rng); 73 | double u3 = u_distribution(rng); 74 | 75 | double qx = sqrt(1.0 - u1) * sin(2.0 * M_PI * u2); 76 | double qy = sqrt(1.0 - u1) * cos(2.0 * M_PI * u2); 77 | double qz = sqrt(u1) * sin(2.0 * M_PI * u3); 78 | double qw = sqrt(u1) * cos(2.0 * M_PI * u3); 79 | 80 | if (is3D) { 81 | gtsam::Point3 t(dx, dy, dz); 82 | gtsam::Rot3 R( 83 | Eigen::Quaternion(qw, qx, qy, qz).toRotationMatrix()); 84 | 85 | gtsam::Pose3 meas(R, t); 86 | // gtsam::noiseModel::Diagonal::shared_ptr noise = 87 | // gtsam::noiseModel::Diagonal::Sigmas(sigmas); 88 | 89 | gtsam::BetweenFactor lc(keys[i], keys[j], meas, 90 | inlier_model); 91 | 92 | graph.add(lc); 93 | } else { 94 | gtsam::Point2 t(dx, dy); 95 | // Sample rotation from -pi to pi 96 | gtsam::Rot2 R(M_PI * (2.0 * u1 - 1.0)); 97 | 98 | gtsam::Pose2 meas(R, t); 99 | 100 | gtsam::BetweenFactor lc(keys[i], keys[j], meas, 101 | inlier_model); 102 | graph.add(lc); 103 | } 104 | } 105 | 106 | return graph; 107 | } 108 | 109 | double hybrid_error(const dcsam::HybridFactorGraph& hfg, 110 | const dcsam::DCValues& values) { 111 | double dcError = 0.0; 112 | for (auto dcfactor : hfg.dcGraph()) { 113 | dcError += dcfactor->error(values.continuous, values.discrete); 114 | } 115 | double discreteError = 0.0; 116 | for (auto dfactor : hfg.discreteGraph()) { 117 | discreteError -= log(dfactor->operator()(values.discrete)); 118 | } 119 | return log(hfg.nonlinearGraph().error(values.continuous)) + dcError + 120 | discreteError; 121 | } 122 | 123 | void writeDiscreteMarginals(const gtsam::KeySet& discreteKeys, 124 | const gtsam::DiscreteMarginals& discreteMarg, 125 | const std::string& fname) { 126 | std::ofstream file(fname); 127 | for (const gtsam::Key& key : discreteKeys) { 128 | // Construct a discrete key from gtsam::Key plus cardinality (2 for 129 | // inlier/outlier) 130 | gtsam::DiscreteKey dk(key, 2); 131 | // Recover probabilities from the marginal conditioned on continuous 132 | // states. 133 | gtsam::Vector probabilities = discreteMarg.marginalProbabilities(dk); 134 | 135 | // We have probabilities[0] = p(inlier | C, meas) and probabilities[1] = 136 | // p(outlier | . ) 137 | double outlier_prob = probabilities[1]; 138 | file << outlier_prob << std::endl; 139 | } 140 | } 141 | -------------------------------------------------------------------------------- /data/pointclouds/bunny_sparse100_part1.xyz: -------------------------------------------------------------------------------- 1 | 0.6500 -4.5800 3.8600 2 | -1.3400 -0.8600 12.8900 3 | -3.8600 -4.6300 4.2400 4 | -2.2500 -0.6100 12.6200 5 | -3.5800 -4.4400 4.5100 6 | -3.9800 -4.4400 4.6500 7 | -4.1900 -4.3500 4.7800 8 | -4.4000 -4.2500 4.9100 9 | -3.6400 -2.5300 12.5400 10 | 2.4400 -2.5800 12.2900 11 | -6.2000 -4.3500 14.9700 12 | 4.4200 -2.8700 5.2800 13 | -2.8400 -0.8800 12.5400 14 | -1.4500 -3.4600 12.0900 15 | -1.1000 -4.0600 11.4100 16 | -1.9700 -3.2500 12.0800 17 | 0.6400 -5.6300 6.2000 18 | -0.6600 -5.6000 6.3300 19 | -2.5100 -4.0000 6.3100 20 | -3.7700 -4.4800 6.4800 21 | 0.9200 -2.0200 13.0700 22 | 4.4800 -2.3700 6.5100 23 | -9.1800 -2.1300 12.6900 24 | 1.9600 -3.4700 11.6800 25 | 0.8400 -5.5500 7.1700 26 | 0.1600 -5.8700 7.3300 27 | -2.4900 -4.3100 7.3200 28 | -4.8600 -4.6700 7.4800 29 | 4.1600 -1.0600 10.5600 30 | -7.3700 -5.8900 12.4600 31 | 1.4300 -5.4400 7.8600 32 | -0.6400 -5.8600 8.0100 33 | -3.2600 -4.6200 8.0500 34 | -5.3400 -4.9000 8.1900 35 | -6.1600 -3.5000 15.4700 36 | -2.4700 -3.3500 11.8000 37 | 1.2400 -5.5400 8.5600 38 | -0.6500 -5.7600 8.7000 39 | -2.6500 -4.6300 8.7500 40 | -4.6400 -4.9500 8.9000 41 | -0.1700 -4.6300 10.0800 42 | -6.6500 -4.9200 14.5600 43 | 0.4400 -5.5500 9.2500 44 | -2.7500 -4.7000 9.3200 45 | -5.4400 -4.9800 9.4600 46 | -0.0400 -5.2600 9.7800 47 | 1.5800 -4.8400 9.6300 48 | -1.1200 -5.0100 9.7700 49 | -3.3700 -4.5500 9.8700 50 | -5.2500 -4.7900 10.0200 51 | -0.6700 -0.9000 13.0400 52 | 0.7600 -3.5300 12.1000 53 | 0.1300 -4.4000 10.3100 54 | -2.5800 -4.3800 10.4300 55 | -4.8800 -4.4700 10.5700 56 | -6.9000 -4.3600 10.6900 57 | 4.4000 -0.6400 10.0100 58 | 1.3000 -3.9300 10.8500 59 | -0.0700 -4.3100 11.0000 60 | -0.5800 -4.2900 11.1400 61 | -4.5900 -1.9700 13.5100 62 | -1.5300 -5.4800 3.9000 63 | -0.1000 -4.8600 4.1000 64 | 2.1900 -4.1900 4.3600 65 | -6.2200 -4.8600 13.8300 66 | 5.2600 -1.7800 4.6600 67 | -4.3700 -1.1400 15.5100 68 | -6.3000 -4.9200 14.1100 69 | -3.7900 -0.4200 16.0900 70 | 1.7200 -4.8800 5.3500 71 | 2.3800 -4.5800 5.5000 72 | 2.9600 -4.0300 5.6400 73 | 3.9400 -3.0200 5.7700 74 | 4.0700 -2.8600 5.9000 75 | 4.2800 -2.6400 6.0300 76 | -5.8300 -4.7000 12.8300 77 | 5.5800 -2.3400 6.3500 78 | 6.0200 -1.7700 6.4800 79 | 1.8800 -4.7900 9.5300 80 | 3.7900 -3.4900 9.5500 81 | -5.4600 -3.7400 14.5300 82 | 1.7100 -3.3300 12.0600 83 | 3.2900 -3.9800 9.5600 84 | 1.8800 -5.2400 7.4000 85 | 2.1600 -5.1100 7.5400 86 | 2.2700 -5.0900 7.6800 87 | 2.0100 -5.2400 7.8100 88 | 1.5700 -5.3500 7.9300 89 | -6.4600 -5.8200 11.7200 90 | -5.3900 -4.2800 11.6900 91 | -5.2400 -4.3100 12.6900 92 | -5.1800 -4.2300 12.6900 93 | -4.2800 -0.9300 15.9400 94 | -4.7800 -3.7700 12.5500 95 | -4.4700 -3.0500 12.8200 96 | -5.8700 -4.9700 12.5500 97 | -5.6400 -3.9900 14.2500 98 | -5.6100 -3.8700 14.2400 99 | -9.0000 -1.4200 12.0000 100 | 5.2800 0.0400 4.7700 101 | -4.7800 -1.2600 13.7100 102 | 5.9900 -0.6000 5.5300 103 | -8.7200 -4.8800 11.5500 104 | -4.7500 -1.5600 13.8600 105 | 6.1900 -0.8800 6.5100 106 | 6.0900 -1.3900 6.7800 107 | 6.0100 -0.8800 7.0600 108 | -8.9300 -3.7200 12.0100 109 | -5.0100 -1.9800 14.9300 110 | -4.9300 -2.2800 14.1600 111 | -8.7700 -2.6200 9.3000 112 | -8.9600 -4.5300 12.0200 113 | -7.5900 -4.3100 15.0100 114 | -0.1800 -4.9200 9.9900 115 | -1.7700 -2.7300 12.4100 116 | -6.7800 -3.6200 15.4600 117 | -6.4600 -3.1300 15.6000 118 | 0.0900 -3.5000 12.3200 119 | -8.5600 -1.3900 10.4900 120 | -8.6000 -1.8900 15.1700 121 | -5.8100 -1.0400 15.7300 122 | -2.6600 -1.9200 12.5200 123 | -3.8200 -1.6100 12.8200 124 | -8.6100 -4.1800 14.0700 125 | 2.5200 -0.2400 12.3300 126 | 3.7500 -0.7200 11.1900 127 | -7.3400 -1.0600 15.5200 128 | -5.8700 -3.0000 15.5400 129 | -8.5700 -2.7600 15.2400 130 | 1.5800 -0.5400 12.9100 131 | 3.7500 -1.2700 11.2400 132 | 5.2000 -1.7900 7.1300 133 | -6.7600 -0.6500 15.5300 134 | 0.9300 -0.7800 13.1200 135 | -3.2100 -4.8900 3.6600 136 | -7.0200 -1.4900 3.8200 137 | -5.8300 -2.4000 3.9700 138 | -5.9200 -4.5000 4.3300 139 | -7.1400 -4.3600 10.0800 140 | -1.7100 -5.4000 9.2000 141 | -6.6200 -4.7300 8.3300 142 | -1.9000 -5.6600 8.2500 143 | -2.3500 -4.5200 7.3500 144 | -7.6500 -5.5600 11.7600 145 | -8.2200 -3.3100 10.4500 146 | -8.4900 -3.2100 8.9600 147 | -8.6200 -3.0200 9.7700 148 | -7.9100 -3.8900 9.8000 149 | -5.3000 -2.7900 5.9400 150 | -1.9500 -5.1300 7.3800 151 | -1.2900 -5.3100 6.2600 152 | -6.2800 -4.9200 9.1500 153 | -4.2700 -4.3400 6.7100 154 | -1.3200 -5.4900 6.8300 155 | -5.7800 -0.8700 15.8000 156 | -5.4500 -1.5900 5.7000 157 | -4.9900 -0.4400 16.5600 158 | -5.4500 -2.7500 4.3800 159 | -5.5000 -3.3600 4.6700 160 | -5.7200 -0.6600 5.0800 161 | -5.4500 -1.3500 5.4800 162 | -5.7500 -0.5600 5.9000 163 | -8.8700 -2.8000 13.9200 164 | -5.2700 -4.2500 6.8500 165 | -7.9800 -3.0600 7.7600 166 | -8.5000 -2.3000 8.2000 167 | -8.5200 -1.4700 14.8800 168 | -8.7400 -1.2100 8.8700 169 | -8.6600 -1.7800 14.0500 170 | 5.4700 0.2900 6.8000 171 | -1.9100 -0.3800 12.6600 172 | -4.5400 -4.2500 6.7500 173 | 2.8800 0.2300 3.7000 174 | 3.4100 -0.4500 3.6100 175 | -3.8700 -0.3700 3.4000 176 | 0.1300 -0.9400 3.4600 177 | 2.6600 -1.4100 3.4600 178 | 2.5100 -1.5600 3.4800 179 | 0.5700 -1.5800 3.4100 180 | -0.2200 -1.3100 3.8100 181 | -1.6100 -1.3200 3.8200 182 | -3.1100 -1.7300 3.3700 183 | -5.3400 -1.6700 3.3500 184 | -6.2000 -1.7200 3.3800 185 | -6.8200 -1.7300 3.4900 186 | -7.3700 -2.3400 6.7500 187 | 3.9000 0.1300 3.9400 188 | 4.3400 -2.5200 4.4500 189 | 2.6700 -3.0500 3.8300 190 | 0.8000 -2.9400 3.9200 191 | -1.5500 -2.9100 3.8400 192 | -4.5000 -3.1400 3.3800 193 | -6.5300 -0.6000 6.2200 194 | -4.7200 -3.9500 6.4700 195 | -0.7500 -3.4800 3.9100 196 | -4.7300 -3.5800 3.4400 197 | -7.0200 -0.9200 6.3900 198 | -5.7700 -4.1600 6.8800 199 | -1.7300 -3.8900 3.9100 200 | -4.7700 -4.0800 3.4600 201 | -6.4400 -1.8900 5.9800 202 | -4.7100 -4.3100 7.0600 203 | -0.1900 -4.8900 3.5800 204 | -3.1500 -4.7600 3.5000 205 | -6.1500 -4.5100 3.5600 206 | -7.5100 -1.7700 6.7900 207 | -4.8400 -0.6800 14.4200 208 | -------------------------------------------------------------------------------- /data/pointclouds/bunny_sparse100_part2.xyz: -------------------------------------------------------------------------------- 1 | -3.7400 0.2500 17.1200 2 | -3.1400 0.0200 12.5400 3 | -1.9500 -0.9900 12.8000 4 | -6.0100 0.1800 15.5800 5 | 0.3900 -1.7800 13.1500 6 | -6.7400 0.3700 15.4900 7 | -5.0900 -0.7000 14.4700 8 | -7.8100 1.1700 11.6300 9 | 1.0100 -1.9200 13.0300 10 | -3.9700 0.7400 17.3400 11 | -8.0700 0.7900 14.3200 12 | -6.9900 2.4500 16.5900 13 | 0.5200 -1.9900 13.1100 14 | 1.9500 -2.0700 12.6200 15 | 4.3900 -1.6000 9.3200 16 | -7.4100 1.3100 11.2600 17 | -3.0900 0.6900 17.7200 18 | -2.9900 -0.2000 12.5400 19 | -8.4300 -0.7000 7.6800 20 | -3.8900 0.0000 15.2200 21 | -8.6900 0.2200 10.2200 22 | -2.6500 0.4300 15.6600 23 | -2.6600 2.9000 9.1900 24 | -1.8200 1.7900 17.8700 25 | -5.2700 -1.0900 14.6300 26 | 3.9300 -2.2700 10.2800 27 | -4.1300 -0.2000 15.3600 28 | -3.9300 0.0600 15.0700 29 | -1.5000 2.6800 18.1600 30 | 2.0800 0.1900 3.5800 31 | 2.1000 0.9900 3.8600 32 | 4.9500 -1.2600 4.4700 33 | 2.2600 1.6800 4.3000 34 | -2.7800 2.3700 10.6800 35 | 5.0700 -0.2700 5.0300 36 | -4.8900 -0.2200 13.5500 37 | 5.7600 -2.0300 5.5300 38 | 3.4500 0.6700 5.4300 39 | 4.4700 -1.3100 9.0400 40 | -5.9400 3.3900 15.3700 41 | -8.1200 0.9700 10.7400 42 | 5.0600 -0.3100 6.5200 43 | -7.3400 -1.1000 6.3700 44 | 5.9000 -1.7400 6.7900 45 | 4.0400 0.6300 6.7400 46 | -0.7300 2.6300 16.9800 47 | -0.8000 2.2500 16.6800 48 | 4.5300 -0.7200 7.3600 49 | 3.9000 0.8400 7.4300 50 | -8.7600 -0.7700 10.7700 51 | -4.7800 -0.6300 13.4000 52 | 4.5000 -1.0100 8.7600 53 | 4.5300 -1.3200 8.2000 54 | 4.1300 0.7200 8.3000 55 | -4.2400 -0.0700 12.8700 56 | -0.8800 2.9700 18.2100 57 | -1.0000 2.7400 18.3900 58 | -6.0000 -1.3300 15.5500 59 | -6.0900 4.7100 16.9400 60 | 5.6300 -1.0600 7.0100 61 | -3.3600 -0.6300 12.6800 62 | -4.4900 -1.3300 12.8200 63 | 3.1000 -0.4000 11.7400 64 | 3.2100 -0.6000 11.6800 65 | 3.5000 -0.8800 11.3200 66 | 3.7700 -1.1500 10.9300 67 | -5.6900 -0.7100 15.5700 68 | -0.9700 -1.5900 13.0300 69 | -6.8100 3.5600 17.0500 70 | -6.2200 3.1300 16.4900 71 | -2.4400 -1.5200 12.6100 72 | -8.8400 -1.0700 10.5000 73 | 0.9700 -0.7200 13.0700 74 | 2.4300 -1.5600 12.3700 75 | -3.2100 -1.4700 12.5500 76 | -1.0900 2.3600 10.5900 77 | -6.9300 -0.4300 3.9600 78 | -3.0500 2.7800 8.8700 79 | -4.6300 1.1400 15.6100 80 | -5.3700 2.6600 8.8400 81 | -4.2100 1.3800 16.0700 82 | -5.6000 2.3600 10.4000 83 | -1.7100 2.4400 17.4200 84 | -6.9200 5.3300 17.0800 85 | -6.4400 1.0900 4.1600 86 | -7.1200 3.2200 15.5500 87 | -5.8600 0.9400 4.5300 88 | -4.0300 1.8900 4.6300 89 | -7.5900 3.9700 16.6700 90 | 4.5000 -0.6400 6.9400 91 | -6.6700 5.1900 15.5400 92 | -2.8000 2.2900 5.3700 93 | -5.4800 0.9200 5.7500 94 | -8.3200 0.6000 14.0400 95 | -2.1700 2.1000 18.1500 96 | -2.6800 2.6900 6.0700 97 | 3.3000 0.9900 10.4600 98 | -7.1900 0.6800 6.7100 99 | -6.8000 1.4100 13.7000 100 | -5.4700 2.6600 8.9800 101 | -9.0500 0.0700 13.3600 102 | -9.2700 -0.9200 13.3700 103 | -8.4000 0.3200 14.8700 104 | 1.6300 1.5700 11.2400 105 | -3.1400 2.8300 7.5200 106 | -1.7800 1.9100 11.4700 107 | -8.1000 1.1700 8.1400 108 | -8.6900 -0.1900 8.3300 109 | -8.4000 0.3200 14.4600 110 | -8.5500 0.7000 9.2700 111 | -2.5800 3.7000 8.4700 112 | -9.1200 0.1700 12.5400 113 | -7.9500 1.5600 9.0900 114 | -3.8600 3.1000 3.7900 115 | 3.2300 1.5000 9.4300 116 | -1.6600 2.2600 18.6800 117 | -3.1100 1.6200 17.6500 118 | -3.4000 1.8900 11.5100 119 | -2.3500 2.0300 11.1600 120 | 0.2300 1.4400 11.9300 121 | -0.0500 3.1900 9.6100 122 | 0.3200 2.4600 9.8900 123 | 1.4300 2.4300 9.5900 124 | -5.7400 1.4500 3.8300 125 | 1.5400 1.8900 10.4100 126 | -2.2600 0.9300 12.2200 127 | -1.3200 1.2600 12.0300 128 | 2.1300 0.5800 12.0300 129 | -5.7200 0.8800 14.1400 130 | -1.9900 2.3100 10.8900 131 | 4.4000 -0.1300 6.2400 132 | 1.4200 0.8800 12.2500 133 | 2.8700 1.3600 10.3900 134 | -0.6500 3.7100 9.0800 135 | -1.1500 -0.0800 12.8600 136 | -5.1900 0.8400 13.2300 137 | -5.6800 1.5500 11.9800 138 | 0.7800 0.1900 12.8600 139 | -5.3000 1.6700 3.4800 140 | 1.9700 2.3000 9.3200 141 | 2.2800 -0.1300 12.3100 142 | -1.9000 0.5500 12.4600 143 | -1.9000 3.0100 3.6500 144 | -3.2000 1.4700 15.7900 145 | -5.9500 1.4300 3.7200 146 | -5.5500 1.4900 3.8800 147 | -2.5500 2.0900 17.2700 148 | 0.5900 1.9900 11.0200 149 | -1.5100 2.9200 4.5000 150 | -0.4000 3.0200 4.6700 151 | 1.1700 2.6200 4.7900 152 | 2.7000 1.7300 4.8800 153 | 4.0700 0.2800 4.9200 154 | -1.8200 2.4000 17.4200 155 | -4.3500 1.4400 5.0500 156 | -1.8300 2.2000 16.9700 157 | -1.3700 3.5000 5.5500 158 | -0.2800 3.3600 5.6900 159 | 0.5100 3.2100 5.8300 160 | 1.7800 2.7100 5.9500 161 | -8.0100 1.2500 12.6600 162 | -2.2700 2.5900 10.1600 163 | -5.1600 1.3700 6.0400 164 | -3.2400 1.6400 6.2200 165 | -0.4600 3.6000 6.5600 166 | 2.1700 2.6700 6.6500 167 | -5.9000 1.3600 12.3800 168 | -5.6600 1.4400 6.6000 169 | -2.2600 3.7300 6.9700 170 | 1.0100 3.2700 7.1100 171 | -7.2900 1.4800 12.6700 172 | -6.4400 1.7500 7.0500 173 | -3.2700 2.2900 7.2700 174 | 0.6300 3.4700 7.5500 175 | -7.0900 1.5200 12.8300 176 | -6.6100 2.1200 7.5100 177 | -3.9000 2.2200 7.6800 178 | -0.7400 3.8800 7.9900 179 | 2.1500 2.5800 8.0600 180 | -6.0000 1.3600 12.5300 181 | -4.7800 2.5100 8.1200 182 | -1.7400 4.0300 8.4100 183 | 1.5800 2.9300 8.5000 184 | -7.3900 1.4400 12.3800 185 | -5.3700 2.6200 8.5500 186 | -2.3600 3.7200 8.8000 187 | -1.9400 2.5500 3.3700 188 | -3.9100 2.7300 3.3500 189 | 0.0200 1.5900 3.5600 190 | -2.6600 2.1100 3.6800 191 | 0.8700 0.9400 3.7400 192 | -2.4000 1.6300 3.8700 193 | 0.3400 0.7000 3.9300 194 | 1.2300 -0.2400 3.4100 195 | 1.7900 -0.5200 3.4900 196 | 1.9300 -0.7300 3.5200 197 | 2.6100 -1.1600 3.4700 198 | 3.2800 -1.4600 3.5600 199 | 3.7300 -1.5800 3.7900 200 | 4.3300 -1.6600 4.0800 201 | 4.2200 -1.8500 4.0500 202 | 3.9900 -2.0500 3.9700 203 | 3.6500 -2.2200 3.8700 204 | -7.6400 -1.2100 6.7600 205 | -5.6700 -0.5000 3.3500 206 | -0.6700 -1.7100 3.8400 207 | -6.7100 3.3500 14.7100 208 | -6.7000 0.4400 6.2600 209 | -6.1800 -0.8400 5.8300 210 | -7.2800 -0.7700 6.3600 211 | -1.5400 1.6500 16.2200 212 | -4.7200 0.4900 14.5800 213 | -1.8900 1.1400 15.8700 214 | -6.3000 4.7200 15.1500 215 | -6.0800 3.0100 14.9700 216 | -2.7400 1.5300 15.9200 217 | -------------------------------------------------------------------------------- /data/pointclouds/dragon_sparse100_part1.xyz: -------------------------------------------------------------------------------- 1 | 3.2027 4.8938 5.9150 2 | 3.8775 4.7537 5.9375 3 | 2.6777 4.7008 6.6375 4 | 2.4426 4.6138 6.7075 5 | 3.7977 4.5104 5.6925 6 | 2.5377 4.4388 6.3080 7 | 3.1575 4.3688 7.0575 8 | -2.4323 4.3338 17.5545 9 | 2.7477 4.2638 6.3654 10 | 3.6168 4.2287 6.6375 11 | 2.8177 4.2059 7.5825 12 | 2.8527 4.1588 7.6825 13 | 2.6505 4.1238 7.6875 14 | -3.7623 4.0888 5.8366 15 | -2.1873 4.1001 16.2275 16 | -3.0623 4.0618 6.1825 17 | -2.9923 4.0537 16.2775 18 | 2.8877 4.0188 6.4667 19 | -3.4123 4.0188 16.4996 20 | 4.3303 3.9837 6.5675 21 | -3.6573 4.0082 16.7875 22 | -2.4193 3.9488 6.6725 23 | -2.7823 3.9488 16.7811 24 | -2.7823 3.9485 6.8825 25 | -3.4570 3.9138 17.0325 26 | 4.0777 3.8974 6.8825 27 | -3.7623 3.9036 16.4025 28 | 2.7827 3.8469 6.7075 29 | -3.5873 3.8696 16.1225 30 | -3.5873 3.8087 6.4775 31 | -3.6926 3.8087 16.1925 32 | -8.2073 3.7738 6.6156 33 | -4.1123 3.7746 17.1375 34 | 4.3227 3.7388 6.2872 35 | -3.5873 3.7568 15.0725 36 | -2.5820 3.7037 5.6925 37 | 3.6927 3.7364 7.1625 38 | -2.6332 3.7037 16.5775 39 | 4.2877 3.6688 6.2598 40 | -3.6223 3.6688 14.7823 41 | -4.6373 3.6880 17.9425 42 | -7.9273 3.6337 6.6992 43 | -2.6639 3.6337 15.3525 44 | -4.5323 3.5987 5.4100 45 | -2.2223 3.6298 6.9175 46 | -2.4323 3.6217 7.6175 47 | -4.1823 3.6014 16.8925 48 | -8.4189 3.5638 6.3925 49 | 3.7277 3.5755 7.3725 50 | -2.8249 3.5709 14.9740 51 | -8.5573 3.5287 5.7946 52 | -1.9773 3.5300 7.1625 53 | 1.3477 3.5421 13.6725 54 | -4.6023 3.5287 17.1385 55 | 4.5327 3.4938 6.3672 56 | -2.6423 3.4938 7.6333 57 | 0.9277 3.5210 13.1475 58 | 2.0827 3.5206 14.5475 59 | -4.0282 3.4938 17.7675 60 | -5.1273 3.4904 6.8125 61 | 3.4477 3.4908 8.2125 62 | 1.2777 3.4832 13.0425 63 | 2.7477 3.4587 14.8163 64 | -2.6073 3.4237 5.6302 65 | 2.2687 3.4358 7.2628 66 | 4.1477 3.4274 8.5275 67 | -0.2273 3.4372 11.1525 68 | 4.1827 3.4336 13.1125 69 | 3.5177 3.4565 14.5475 70 | -4.6373 3.4579 17.7675 71 | 4.8126 3.3888 6.8475 72 | 3.3777 3.4144 8.4225 73 | -0.7523 3.3911 10.5925 74 | 4.8827 3.3898 12.6925 75 | 4.1827 3.4235 14.0225 76 | -4.9173 3.3888 16.9006 77 | -8.3195 3.3705 6.5394 78 | -1.9162 3.3538 8.0725 79 | -0.8573 3.3702 10.3475 80 | 4.8477 3.3790 11.9575 81 | 0.6477 3.3538 14.0108 82 | -4.6788 3.3538 17.1375 83 | -7.9273 3.3188 6.7043 84 | -6.6323 3.3527 8.0725 85 | 4.6027 3.3190 10.3475 86 | 4.9877 3.3376 12.7625 87 | 3.6227 3.3507 14.8625 88 | -2.8942 3.2837 5.3425 89 | -3.0623 3.2837 7.2966 90 | -1.2073 3.2837 9.2969 91 | -0.9273 3.3179 11.5025 92 | 0.8927 3.2837 14.4603 93 | -4.1123 3.2942 17.7325 94 | 4.3927 3.2488 7.2849 95 | 2.3522 3.2488 9.1575 96 | 1.0327 3.2666 11.9925 97 | -3.9023 3.2488 14.4817 98 | -4.1823 3.2661 17.9075 99 | -1.7721 3.2137 7.3725 100 | -1.7297 3.2137 9.2275 101 | -0.9273 3.2455 11.9225 102 | -4.2102 3.2137 14.5825 103 | -2.7473 3.2099 5.5525 104 | -2.7825 3.1788 7.7925 105 | -1.7323 3.2134 9.2275 106 | -1.2423 3.1788 11.4007 107 | -4.5323 3.1986 14.4775 108 | -4.9523 3.1981 17.3475 109 | 3.7277 3.1438 6.5600 110 | -1.6623 3.1595 8.0725 111 | 0.0877 3.1629 10.1375 112 | 5.2677 3.1474 13.5675 113 | -5.1623 3.1661 16.9625 114 | -8.3123 3.1278 6.6725 115 | -1.0033 3.1087 8.5275 116 | 0.4377 3.1274 10.7325 117 | 4.6027 3.1260 14.5825 118 | -0.9273 3.1087 18.8049 119 | -6.5273 3.0789 7.3025 120 | -0.3323 3.0967 9.3325 121 | 1.5577 3.0738 12.3388 122 | 4.1827 3.1080 14.8975 123 | -0.4580 3.0738 19.0625 124 | -6.4923 3.0714 7.1625 125 | -2.2923 3.0692 9.3675 126 | 5.6527 3.0460 12.7625 127 | -3.0445 3.0388 16.2275 128 | -5.8630 3.0038 5.9725 129 | 4.7777 3.0266 7.7575 130 | 5.0577 3.0299 10.3475 131 | -3.6223 3.0161 14.0925 132 | -5.4067 3.0038 16.5075 133 | -6.2832 2.9688 6.1475 134 | -1.1373 2.9970 8.0375 135 | -1.8723 3.0002 10.5225 136 | -0.4279 2.9688 13.6025 137 | -5.5801 2.9688 16.1225 138 | 5.3027 2.9589 6.0425 139 | -1.5923 2.9641 7.4775 140 | -2.4323 2.9337 9.5029 141 | 3.0977 2.9633 12.9025 142 | -2.8523 2.9376 15.3175 143 | -0.6180 2.9337 19.3425 144 | -3.8323 2.8988 7.3149 145 | 1.9427 2.9328 9.1575 146 | 2.8177 2.9089 12.8675 147 | -5.3023 2.8988 16.0153 148 | -9.0584 2.8638 5.8675 149 | -3.8673 2.8789 7.7925 150 | 2.4680 2.8638 10.0675 151 | -4.3542 2.8638 14.0575 152 | -3.0046 2.8638 16.2275 153 | -9.0123 2.8476 6.0425 154 | -0.9273 2.8566 7.9675 155 | 5.2327 2.8629 10.3475 156 | -3.0973 2.8319 13.7425 157 | -5.3373 2.8532 15.9475 158 | -3.2373 2.7938 5.4477 159 | -6.8773 2.7938 7.4446 160 | -2.2934 2.7938 9.9975 161 | -3.4123 2.7938 13.2552 162 | 3.8327 2.7938 15.3525 163 | -1.1036 2.7938 19.1325 164 | 5.1277 2.7587 6.8547 165 | -2.7123 2.7587 9.4347 166 | -4.1823 2.7771 12.8325 167 | 1.4527 2.7587 15.3701 168 | -1.6409 2.7689 18.3196 169 | -8.8723 2.7283 6.2875 170 | -7.4023 2.7391 8.5275 171 | 5.8583 2.7237 11.5025 172 | -4.9523 2.7237 14.1558 173 | -3.5617 2.7237 17.1725 174 | -2.7123 2.6888 5.9604 175 | -1.0323 2.7237 7.6175 176 | 0.6477 2.7135 10.4175 177 | -4.7106 2.6888 13.4975 178 | -6.2807 2.6888 16.1925 179 | -8.8373 2.6538 5.9491 180 | -0.9273 2.6654 7.6525 181 | -2.5023 2.6565 9.9275 182 | -3.4139 2.6538 12.9725 183 | 1.6277 2.6730 15.4925 184 | -2.3273 2.6538 18.7121 185 | -8.5855 2.6188 6.6375 186 | 5.0227 2.6384 9.7175 187 | 5.8627 2.6408 13.4275 188 | -2.6826 2.6188 15.9475 189 | -3.2655 2.5838 5.6575 190 | 5.1977 2.6016 7.0225 191 | 2.6427 2.6168 10.5225 192 | -2.9995 2.5838 13.3575 193 | -2.6423 2.5861 15.9125 194 | -8.1723 2.5487 5.8295 195 | -1.1023 2.5487 7.2685 196 | 2.6875 2.5487 10.6275 197 | -4.9547 2.5487 13.6375 198 | -5.8273 2.5487 15.7028 199 | -3.7973 2.5138 5.5487 200 | -1.0673 2.5190 7.2675 201 | 2.5027 2.5176 10.4175 202 | -2.5023 2.5441 14.0225 203 | -2.5023 2.5225 15.8775 204 | -2.0473 2.5138 18.8196 205 | 1.4954 2.4788 6.9525 206 | -2.1523 2.4788 10.8040 207 | -5.5716 2.4760 14.1167 208 | -2.0473 2.5049 16.0525 209 | -4.4273 2.4438 5.6033 210 | -1.0663 2.4438 7.1625 211 | 2.9927 2.4470 11.2925 212 | -5.9258 2.4625 14.1404 213 | 2.9577 2.4438 15.7504 214 | -3.2023 2.4603 18.4675 215 | 5.6177 2.4088 6.5799 216 | -2.6773 2.4289 9.8925 217 | 5.9546 2.4088 13.7775 218 | 0.7177 2.4088 15.2597 219 | -6.4223 2.4088 17.2302 220 | 6.0727 2.4049 5.7625 221 | -0.2026 2.3737 8.2125 222 | -4.4273 2.3738 11.5025 223 | -5.0830 2.3728 14.1013 224 | 2.4920 2.3737 15.7725 225 | -3.3773 2.3737 17.6813 226 | 3.6927 2.3387 5.7456 227 | 4.5237 2.3387 8.5975 228 | -5.6873 2.3562 11.2225 229 | -5.8460 2.3290 14.1393 230 | -6.5222 2.3387 15.8075 231 | -3.6118 2.3387 18.4675 232 | 5.8602 2.3038 6.3925 233 | -6.9123 2.3376 9.6475 234 | -5.8262 2.3038 12.5175 235 | -2.0590 2.3038 15.1075 236 | -6.7723 2.3040 16.5075 237 | 2.9927 2.2780 5.4825 238 | -7.2623 2.2954 6.8825 239 | -6.8423 2.2891 9.7175 240 | -1.5051 2.2688 12.5175 241 | -0.2973 2.2894 14.6525 242 | 1.5577 2.2944 15.9475 243 | -4.2523 2.2749 17.9075 244 | 3.5177 2.2490 5.5525 245 | 5.5273 2.2338 7.0575 246 | -6.3873 2.2519 9.8575 247 | -3.9692 2.2338 11.7125 248 | -5.1368 2.2224 14.1008 249 | 1.2777 2.2582 15.8775 250 | -6.3873 2.2538 17.5575 251 | 2.7477 2.1990 5.4825 252 | -7.0173 2.2180 7.2325 253 | -6.2123 2.2170 9.9275 254 | -3.4842 2.1988 12.2025 255 | 5.6527 2.2338 14.5825 256 | 1.7677 2.2093 16.0525 257 | -4.1823 2.1988 18.7078 258 | 4.6027 2.1637 5.9407 259 | -5.2323 2.1637 9.0203 260 | -6.2123 2.1976 12.0625 261 | -6.1220 2.1348 14.1639 262 | 0.6127 2.1637 15.6915 263 | -6.3432 2.1637 17.6625 264 | -2.2255 2.1288 5.6575 265 | -0.5758 2.1288 7.4425 266 | -6.9123 2.1368 10.8025 267 | -1.4523 2.1307 12.9725 268 | -0.5423 2.1553 14.8975 269 | -2.2923 2.1522 16.1925 270 | -2.5023 2.0938 5.4626 271 | 4.5233 2.0938 8.4925 272 | 5.9800 2.0938 11.0125 273 | 6.3527 2.0938 13.0102 274 | -0.4023 2.0938 15.1904 275 | 2.0827 2.0938 16.1800 276 | -2.8873 2.0652 5.3425 277 | 1.3127 2.0588 6.9517 278 | -7.2382 2.0588 10.5225 279 | -1.6623 2.0730 12.4825 280 | -5.7520 2.0660 14.4351 281 | -7.2623 2.0588 16.1528 282 | -3.0273 2.0238 5.3031 283 | -0.8573 2.0238 6.9598 284 | 2.6186 2.0238 10.8375 285 | -6.0736 2.0238 12.7975 286 | -1.0673 2.0238 14.4234 287 | -2.4365 2.0238 15.9825 288 | -4.2523 2.0266 18.9575 289 | 5.8810 1.9888 6.6375 290 | -2.7136 1.9888 10.2425 291 | 2.8303 1.9888 12.3425 292 | -6.5534 1.9888 13.9875 293 | 0.9627 2.0117 15.8075 294 | -4.4980 1.9888 18.3975 295 | -8.6273 1.9765 6.2175 296 | 5.3727 1.9550 9.8925 297 | 6.3527 1.9700 12.0975 298 | -2.2929 1.9537 13.9525 299 | 1.0327 1.9788 15.7025 300 | -6.9823 1.9753 17.4875 301 | 6.3758 1.9188 6.0425 302 | -2.8173 1.9188 10.1019 303 | -2.8647 1.9339 12.2758 304 | -2.2923 1.9258 14.0925 305 | 1.1727 1.9328 15.7375 306 | -6.9008 1.9188 17.5925 307 | -1.5573 1.8869 6.0775 308 | -7.7873 1.8838 10.0162 309 | 2.9125 1.8838 12.2725 310 | -2.3273 1.8881 14.0225 311 | 0.9277 1.8979 15.5275 312 | -7.3542 1.8838 17.4525 313 | -7.6893 1.8488 5.9375 314 | 0.6810 1.8562 9.5965 315 | -3.0973 1.8488 12.0263 316 | 7.8927 1.8832 13.5675 317 | 5.2677 1.8488 15.3016 318 | -7.5726 1.8488 16.3675 319 | 4.4627 1.8193 5.6225 320 | 4.6279 1.8138 8.7725 321 | -3.0623 1.8431 12.0275 322 | 7.1498 1.8138 13.8125 323 | 1.2764 1.8138 15.5975 324 | -7.3671 1.8138 17.3825 325 | -8.0921 1.7787 6.2875 326 | -7.9273 1.7941 9.9975 327 | 6.8777 1.8001 11.9575 328 | 7.9627 1.7787 13.7955 329 | 0.4027 1.7787 15.1505 330 | -7.5423 1.7787 16.4840 331 | -1.6942 1.7438 5.8325 332 | -3.2373 1.7438 9.6013 333 | -2.2725 1.7404 12.0713 334 | -1.4960 1.7480 13.6145 335 | 5.2327 1.7720 15.2475 336 | -7.1223 1.7777 16.7525 337 | 5.0227 1.7088 5.6920 338 | -3.2723 1.7094 9.5775 339 | 6.5627 1.7088 11.6749 340 | 6.7377 1.7301 13.6025 341 | 5.5127 1.7104 15.1075 342 | -7.0173 1.7382 17.5925 343 | -1.6273 1.7063 5.8675 344 | -3.0941 1.6738 9.8575 345 | 7.5452 1.6738 11.9225 346 | 6.3287 1.6738 13.9525 347 | 0.8577 1.6738 15.3557 348 | -6.8773 1.6738 17.6570 349 | -7.7878 1.6388 6.3225 350 | -4.1123 1.6417 10.9075 351 | -1.8458 1.6460 12.9041 352 | -6.4729 1.6412 14.4593 353 | -8.5573 1.6388 16.3294 354 | 5.2327 1.6038 5.5516 355 | -4.8663 1.6038 9.6475 356 | 7.5906 1.6038 11.8875 357 | 6.4577 1.6265 13.7775 358 | 4.0777 1.6038 15.5021 359 | -3.8323 1.6376 18.8175 360 | 0.0498 1.5687 8.1425 361 | 2.5900 1.5835 10.8495 362 | -1.7673 1.5986 12.8325 363 | -2.3273 1.5687 14.5120 364 | -8.6697 1.5687 16.2625 365 | 1.6934 1.5338 5.9375 366 | 5.5841 1.5338 9.9625 367 | -3.1290 1.5461 12.0194 368 | 6.8777 1.5338 13.9193 369 | -7.6123 1.5338 15.6842 370 | -4.9173 1.4988 5.3403 371 | 4.9177 1.4988 9.1562 372 | -7.4723 1.4988 11.4327 373 | 8.5927 1.5203 13.3575 374 | 5.0519 1.4988 14.9675 375 | -4.4976 1.4988 18.2575 376 | -8.3823 1.4638 7.8587 377 | 6.2647 1.4638 10.8375 378 | 7.8927 1.4638 12.5003 379 | -5.3040 1.4640 14.2717 380 | -6.8087 1.4638 15.9475 381 | -6.9123 1.4288 5.6932 382 | 2.0839 1.4354 9.9429 383 | -3.3980 1.4283 11.6198 384 | 8.7677 1.4288 13.2432 385 | -0.0523 1.4288 14.6541 386 | -6.5973 1.4288 17.8479 387 | 4.5757 1.3938 8.2825 388 | 2.5557 1.4011 10.7351 389 | 2.2227 1.3938 12.4967 390 | 8.6277 1.4135 14.2325 391 | 2.0127 1.4120 15.5975 392 | -2.7823 1.3588 5.3039 393 | -8.4904 1.3588 8.2825 394 | -8.0247 1.3588 10.6275 395 | 1.8727 1.3588 12.2912 396 | 6.9477 1.3588 13.9653 397 | -2.4635 1.3588 15.7725 398 | -3.0623 1.3238 5.4388 399 | -8.5223 1.3353 8.7375 400 | 7.3327 1.3450 10.8375 401 | 6.2827 1.3358 12.6575 402 | -7.8573 1.3455 14.4775 403 | -2.6773 1.3244 16.5775 404 | 7.0527 1.2889 5.8675 405 | -4.2568 1.2888 9.6125 406 | 7.6127 1.3064 11.0475 407 | 9.0127 1.2958 13.1475 408 | 8.5227 1.2888 14.4885 409 | -9.1691 1.2888 16.6825 410 | 7.1227 1.2538 5.7510 411 | 5.2677 1.2538 9.2939 412 | -3.8660 1.2552 10.8205 413 | 8.5227 1.2538 12.5921 414 | 8.4877 1.2650 14.5125 415 | -2.3273 1.2538 16.5285 416 | -3.9830 1.2445 5.6584 417 | -4.1749 1.2188 9.7175 418 | -2.2573 1.2188 11.3605 419 | 9.0477 1.2442 13.3575 420 | 7.7047 1.2188 14.6525 421 | -9.1093 1.2188 16.9275 422 | -0.5486 1.1838 6.9875 423 | 2.6440 1.1838 10.6975 424 | -1.6539 1.1838 12.5175 425 | -6.5273 1.1838 14.3899 426 | -7.5073 1.1838 16.0247 427 | -6.3523 1.1488 5.3807 428 | 1.4877 1.1488 8.5393 429 | -7.9973 1.1488 10.8795 430 | 6.6312 1.1488 12.5525 431 | 8.9888 1.1488 14.2675 432 | -5.8814 1.1569 15.5846 433 | -1.9423 1.1488 16.9625 434 | 7.0177 1.1138 5.3936 435 | 0.3142 1.1138 8.7025 436 | -2.4673 1.1138 10.7317 437 | 2.4327 1.1241 12.6575 438 | -6.9123 1.1138 14.3068 439 | -1.9423 1.1476 15.5625 440 | -2.7123 1.1138 17.1904 441 | 1.8377 1.0788 5.7213 442 | 5.4499 1.0788 9.5075 443 | -3.7973 1.1134 11.3975 444 | 9.1177 1.0788 12.8446 445 | -5.8623 1.0788 14.4448 446 | 3.0277 1.0788 15.4984 447 | -1.8023 1.0844 17.3475 448 | 5.4341 1.0438 7.0225 449 | 7.4027 1.0728 10.3125 450 | 7.6127 1.0690 12.5175 451 | -7.8573 1.0438 14.0230 452 | 7.9277 1.0438 14.9823 453 | -1.5513 1.0536 16.9708 454 | 6.4927 1.0088 6.7981 455 | 0.7527 1.0100 10.0675 456 | 6.0027 1.0299 11.3625 457 | 7.0527 1.0248 12.8325 458 | 7.1227 1.0088 14.3080 459 | -6.5111 1.0234 15.3419 460 | -0.9969 1.0088 17.4525 461 | -8.3473 1.0000 7.0225 462 | 5.4087 0.9738 9.8575 463 | -4.0423 0.9838 10.8725 464 | -6.5852 0.9738 12.7625 465 | 9.0013 0.9738 14.1275 466 | -1.2705 0.9666 14.9649 467 | -9.5723 1.0043 16.7525 468 | 7.1927 0.9387 6.1058 469 | 5.1977 0.9482 9.3675 470 | 5.5357 0.9387 10.5225 471 | 3.2962 0.9387 12.3075 472 | 9.6427 0.9452 13.7075 473 | -2.0595 0.9433 14.8765 474 | -1.7673 0.9387 16.6345 475 | 7.2627 0.9037 5.5498 476 | 4.7427 0.9073 9.1925 477 | 6.4208 0.9100 11.2190 478 | -6.1845 0.9037 13.0425 479 | -6.2473 0.9037 14.4501 480 | 3.5320 0.9037 15.3175 481 | -8.6273 0.9037 17.0387 482 | 6.4927 0.8687 7.0567 483 | -2.9480 0.8615 9.7913 484 | -3.8323 0.8803 11.6075 485 | 8.6277 0.8742 13.3925 486 | -2.2796 0.8745 14.6781 487 | -1.6273 0.8687 15.4658 488 | -3.7273 0.8687 17.6643 489 | 5.4553 0.8337 7.1275 490 | -4.0738 0.8337 9.7525 491 | 5.9672 0.8337 11.9225 492 | -5.3737 0.8337 13.8475 493 | -7.2812 0.8337 14.9325 494 | -7.6168 0.8337 17.0675 495 | 1.7138 0.7988 6.0075 496 | 4.5327 0.8214 9.0525 497 | -3.9373 0.8122 11.4675 498 | 9.1177 0.7988 13.5268 499 | -1.9768 0.8062 14.8445 500 | -9.8523 0.8283 16.9975 501 | 3.6939 0.7752 5.5837 502 | 4.7842 0.7637 8.3875 503 | -4.3573 0.7637 10.7318 504 | 1.9427 0.7637 12.8251 505 | -9.0462 0.7637 14.4425 506 | 8.1027 0.7952 15.1425 507 | -9.1173 0.7637 17.1651 508 | 4.2251 0.7402 5.5640 509 | 4.7443 0.7287 8.3875 510 | 5.2299 0.7287 10.3825 511 | -6.4087 0.7287 12.9375 512 | 7.2627 0.7614 14.3375 513 | -1.4188 0.7287 15.0725 514 | -1.4523 0.7384 17.2425 515 | -1.4173 0.6938 5.8320 516 | 2.1527 0.7190 9.0875 517 | -1.9730 0.6938 11.3975 518 | 7.7877 0.7180 13.8475 519 | 7.8577 0.7055 14.8625 520 | -6.9068 0.6916 16.3174 521 | -3.5575 0.7033 18.0328 522 | 6.0237 0.6782 6.8472 523 | -8.5617 0.6588 9.8575 524 | -7.0739 0.6588 12.2375 525 | -2.8960 0.6588 14.3025 526 | -8.5208 0.6960 14.9981 527 | -1.6623 0.6590 16.5425 528 | -3.3815 0.6743 18.1870 529 | 7.0630 0.6237 6.7425 530 | 2.3627 0.6524 9.2625 531 | -4.3454 0.6237 10.9425 532 | 3.0977 0.6380 13.0775 533 | 8.2077 0.6296 14.3375 534 | 2.4327 0.6338 15.2125 535 | -8.8023 0.6351 17.4175 536 | -4.6615 0.5889 5.7217 537 | 2.2927 0.5893 9.0175 538 | -2.1523 0.6031 10.9075 539 | -3.1323 0.6162 13.2175 540 | 9.2227 0.5888 14.4952 541 | -1.9073 0.6069 15.5275 542 | -8.3473 0.6171 17.5225 543 | 3.4495 0.5275 5.6196 544 | 4.8384 0.5538 8.0025 545 | 6.3795 0.5577 10.3955 546 | 1.6627 0.5785 12.7625 547 | -9.6065 0.5538 14.3725 548 | 3.0627 0.5727 15.1075 549 | -9.1873 0.5538 17.3330 550 | 3.3585 0.5225 5.5990 551 | 5.3377 0.5187 7.4210 552 | -2.6684 0.5380 10.0636 553 | 1.0677 0.5187 12.0583 554 | -5.0923 0.5512 14.1275 555 | -8.2714 0.5175 14.8263 556 | -8.6973 0.5242 16.1225 557 | -5.1273 0.5187 17.9102 558 | -1.0673 0.4837 6.2989 559 | 4.1265 0.4837 9.0875 560 | 0.7132 0.4837 11.1175 561 | -5.6839 0.4837 13.3225 562 | 8.9777 0.4928 14.4775 563 | -9.2795 0.4837 15.1075 564 | -9.1173 0.4837 17.4562 565 | 2.0477 0.4493 5.6575 566 | 1.5776 0.4334 7.4859 567 | -2.7712 0.4459 9.8624 568 | 1.1727 0.4831 12.3075 569 | 0.7877 0.4488 14.3659 570 | -8.6049 0.4647 15.0603 571 | -7.6123 0.4488 17.4213 572 | -1.8023 0.4138 5.5231 573 | 4.5025 0.3643 7.2826 574 | 4.2177 0.4257 9.6125 575 | 3.5177 0.4470 11.5375 576 | 2.1527 0.4173 13.3925 577 | -5.5473 0.4138 14.5251 578 | -1.9773 0.4333 15.9125 579 | -6.7373 0.4249 17.9075 580 | 1.9077 0.3826 6.0775 581 | 4.5744 0.3400 7.5515 582 | 6.5327 0.3788 10.4175 583 | -0.9623 0.4045 12.6925 584 | -6.7023 0.3788 14.2926 585 | -5.5439 0.3976 15.6258 586 | -4.5652 0.3788 17.7675 587 | 2.0127 0.3440 5.8675 588 | 4.5941 0.3339 7.5482 589 | 0.3326 0.3438 10.0675 590 | -7.2273 0.3438 12.0650 591 | -0.0873 0.3749 13.6725 592 | -9.8173 0.3640 14.6525 593 | -9.3623 0.3438 16.5221 594 | -3.6911 0.3438 18.2575 595 | 3.8394 0.3130 6.2833 596 | -0.2486 0.3088 8.0025 597 | 4.2877 0.3088 10.1969 598 | -6.7723 0.3088 12.4708 599 | 0.8129 0.3088 14.0225 600 | 3.1677 0.3209 14.5825 601 | -7.4803 0.2949 16.5064 602 | -3.1673 0.3088 18.3352 603 | 4.5516 0.3004 6.8731 604 | -8.7127 0.2738 8.8075 605 | 4.2177 0.2758 10.2775 606 | -0.9973 0.2899 12.4825 607 | 2.1877 0.3052 13.8475 608 | 2.8877 0.3042 14.3725 609 | -5.4821 0.2535 15.5510 610 | -3.4473 0.2902 17.8725 611 | -1.5573 0.2434 5.8325 612 | -0.2623 0.2724 8.0375 613 | 3.7977 0.2387 10.2164 614 | -1.1723 0.2616 11.9925 615 | 1.4527 0.2390 13.6025 616 | -2.8873 0.2387 14.6226 617 | -7.7202 0.2479 16.5600 618 | -6.8773 0.2038 5.4178 619 | 5.8627 0.2043 7.3025 620 | 8.0327 0.2038 9.0176 621 | -4.3573 0.2138 11.2925 622 | 4.1127 0.2068 13.2525 623 | -6.7723 0.2038 14.3267 624 | -6.0905 0.2225 15.4864 625 | -3.7973 0.2230 17.6625 626 | 3.2936 0.1748 5.6359 627 | 4.7301 0.1516 7.6072 628 | -8.5398 0.1688 9.7525 629 | 4.7427 0.1749 11.9225 630 | 4.3227 0.1775 13.1475 631 | -10.2023 0.1872 14.5475 632 | -9.3273 0.1688 16.7900 633 | 3.4330 0.1580 5.4383 634 | 4.2360 0.1408 7.0133 635 | 7.9575 0.1338 8.6325 636 | 6.7377 0.1338 11.2223 637 | -5.0573 0.1512 13.4975 638 | -8.8168 0.1338 14.9108 639 | -3.0973 0.1338 16.8216 640 | -3.3393 0.0987 5.4825 641 | 1.6977 0.0987 6.6850 642 | 7.4027 0.1302 8.1425 643 | 7.9755 0.0987 11.1525 644 | -10.3423 0.0987 14.1907 645 | -5.8364 0.0956 15.4048 646 | -3.9023 0.0987 17.5105 647 | 6.9477 0.0637 5.6353 648 | 4.3512 0.1045 7.1958 649 | 6.5627 0.0637 9.2523 650 | -0.6123 0.0976 12.2725 651 | -8.6788 0.1036 14.9145 652 | -6.8626 0.0789 16.3307 653 | -6.2123 0.0287 5.3396 654 | 3.9242 0.0367 6.4250 655 | 7.2627 0.0287 8.1667 656 | 6.6708 0.0287 10.6975 657 | -10.3073 0.0287 14.1687 658 | -5.2167 0.0063 15.6985 659 | -4.0366 0.0287 17.5575 660 | 6.9477 -0.0035 5.6925 661 | -0.6123 0.0152 7.4775 662 | -2.6439 -0.0063 9.7525 663 | -4.5323 0.0118 13.5325 664 | -9.6249 -0.0167 15.3783 665 | -4.6023 -0.0063 17.6074 666 | -1.3504 -0.0413 6.1825 667 | 7.8254 -0.0413 7.6875 668 | -8.3823 -0.0413 10.0745 669 | -6.0023 -0.0066 12.7975 670 | -9.7823 -0.0344 15.2475 671 | -4.1473 -0.0412 17.4175 672 | -1.9773 -0.0763 5.5705 673 | 1.4762 -0.0763 7.4075 674 | -2.1173 -0.0758 10.1025 675 | -3.6978 -0.0895 14.1135 676 | -6.3173 -0.0432 15.3175 677 | -9.4258 -0.0763 17.3125 678 | -3.7837 -0.1091 5.5437 679 | 7.7851 -0.1112 7.4075 680 | -4.5323 -0.1112 9.6609 681 | -6.1073 -0.0846 12.6575 682 | -6.2460 -0.1111 15.2676 683 | -9.6073 -0.1112 17.5575 684 | -3.8876 -0.1459 5.5702 685 | -0.8910 -0.1462 7.1975 686 | 6.5251 -0.1462 9.7875 687 | -6.2473 -0.1200 12.5175 688 | -9.7473 -0.1462 15.2839 689 | -9.6073 -0.1462 17.6113 690 | 0.7895 -0.1698 5.7083 691 | 6.8077 -0.1810 8.0025 692 | -0.3673 -0.1813 10.3125 693 | -9.0123 -0.1813 14.1368 694 | -4.7195 -0.1599 16.0537 695 | 2.7127 -0.2163 5.3372 696 | 1.3181 -0.2042 6.3542 697 | -0.4832 -0.2163 8.4575 698 | -0.8923 -0.1976 10.8725 699 | -8.4523 -0.2163 15.1399 700 | -9.3244 -0.2163 17.1725 701 | 0.8387 -0.2512 5.6925 702 | 6.0027 -0.2319 7.7925 703 | -4.4973 -0.2512 9.5791 704 | -4.6723 -0.2226 12.7975 705 | -4.2173 -0.2512 15.3875 706 | -8.4523 -0.2512 18.1657 707 | 1.5855 -0.2973 6.2702 708 | 6.5627 -0.2536 8.4575 709 | -7.7173 -0.2862 11.0897 710 | -9.7823 -0.2862 15.2239 711 | -5.6796 -0.2862 17.5925 712 | 1.5917 -0.2982 6.1184 713 | 6.5277 -0.3022 8.1775 714 | 6.9277 -0.3212 10.9425 715 | -6.4743 -0.3175 15.1609 716 | -7.5073 -0.3212 17.2617 717 | 4.2918 -0.3543 5.9929 718 | 3.2052 -0.3563 8.2125 719 | 6.9754 -0.3563 10.9425 720 | -9.7823 -0.3263 15.2475 721 | -5.5123 -0.3563 17.5143 722 | 4.2937 -0.3715 6.0171 723 | 6.0677 -0.3913 8.4925 724 | -7.0873 -0.3639 11.7475 725 | -9.6073 -0.3698 15.4575 726 | -2.9223 -0.4262 5.3456 727 | -0.9973 -0.4258 7.5125 728 | -1.7323 -0.3916 9.6825 729 | -6.0375 -0.4260 14.6005 730 | -9.1873 -0.4262 17.2163 731 | -1.9773 -0.4362 5.9025 732 | 2.9570 -0.4612 8.5275 733 | 3.6870 -0.4895 12.1558 734 | -9.6073 -0.4612 15.5408 735 | -9.3973 -0.4612 17.9728 736 | 2.3944 -0.4963 6.2175 737 | -1.0323 -0.4963 9.1241 738 | 3.7071 -0.4948 12.3750 739 | -4.8123 -0.4776 16.4725 740 | 6.4577 -0.5043 5.3775 741 | -8.2773 -0.5294 6.9875 742 | -2.5373 -0.5016 9.2625 743 | -4.7703 -0.5355 14.4238 744 | -4.8473 -0.5305 16.5075 745 | -6.7723 -0.5662 5.5452 746 | -1.0582 -0.5662 7.8975 747 | 8.2427 -0.5662 10.2111 748 | -10.0273 -0.5330 14.5475 749 | -5.5123 -0.5659 16.9625 750 | 3.7994 -0.5532 5.6361 751 | 3.4353 -0.6012 8.1075 752 | 6.9827 -0.5939 10.6625 753 | -5.2323 -0.6012 15.0811 754 | -8.1433 -0.6012 17.7675 755 | 4.2747 -0.6565 6.3194 756 | -1.6273 -0.6363 9.1557 757 | -4.9666 -0.6412 14.3304 758 | -6.2473 -0.6363 16.0378 759 | -2.3973 -0.6712 5.6888 760 | 3.4827 -0.6712 8.1760 761 | -7.3673 -0.6504 11.1175 762 | -10.0623 -0.6712 15.0466 763 | -8.1955 -0.6712 17.7675 764 | -1.4173 -0.6843 6.3575 765 | -1.4523 -0.7063 9.3292 766 | -5.4144 -0.7225 14.2549 767 | -10.1673 -0.6994 15.7725 768 | -1.8373 -0.7314 5.8325 769 | 8.1027 -0.7413 7.7242 770 | 7.6895 -0.7413 10.6275 771 | -6.9473 -0.7336 14.3725 772 | -6.0023 -0.7413 16.7539 773 | 2.4513 -0.7762 6.0896 774 | -2.1173 -0.7717 8.7025 775 | 4.0077 -0.7737 11.8175 776 | -9.8523 -0.7763 15.7591 777 | -6.0371 -0.8113 5.5175 778 | -1.1723 -0.8051 6.4275 779 | -3.7273 -0.7870 9.0525 780 | -5.5821 -0.8121 14.2471 781 | -5.5473 -0.7917 16.3675 782 | 2.8814 -0.8462 5.7275 783 | 1.7327 -0.8462 6.5479 784 | -7.9623 -0.8450 9.9975 785 | -5.1273 -0.8339 14.4425 786 | -6.1784 -0.8462 16.7525 787 | -1.6623 -0.8527 5.7975 788 | 5.6225 -0.8813 8.0725 789 | 8.1024 -0.8813 10.1375 790 | -6.9473 -0.8813 14.3595 791 | -8.2423 -0.8813 16.6838 792 | -1.7323 -0.8994 5.6225 793 | 4.0777 -0.9162 7.6559 794 | 3.8915 -0.8687 10.5086 795 | -7.2849 -0.9165 14.9472 796 | 4.1155 -0.9512 5.3425 797 | 4.2997 -0.9400 6.4866 798 | -8.1926 -0.9512 9.0525 799 | -5.7460 -0.9511 14.3139 800 | -8.6623 -0.9512 16.8919 801 | 0.8789 -0.9839 6.1747 802 | -2.6073 -0.9656 8.3875 803 | 3.4782 -1.0010 10.5805 804 | -7.9266 -0.9728 15.1847 805 | 5.2677 -1.0212 5.5094 806 | -2.2051 -1.0212 7.3725 807 | -1.7323 -1.0212 8.7518 808 | -6.7373 -1.0212 14.2890 809 | -8.6973 -1.0212 16.8124 810 | -1.1723 -1.0446 5.8325 811 | 3.6845 -1.0635 7.5763 812 | -7.8223 -1.0322 9.6825 813 | -6.3523 -1.0520 14.7575 814 | -6.9823 -1.0231 16.8925 815 | 0.6872 -1.0912 6.4275 816 | -2.7823 -1.0865 7.9325 817 | 7.8252 -1.0912 10.1725 818 | -9.0283 -1.0904 15.2873 819 | 6.5277 -1.1222 5.4125 820 | 2.4152 -1.1205 6.4680 821 | -2.0473 -1.0926 7.9675 822 | 6.8777 -1.1262 9.9766 823 | -8.4689 -1.1353 14.9999 824 | -2.3273 -1.1612 5.3091 825 | 1.3477 -1.1612 6.4450 826 | 2.3643 -1.1612 8.4575 827 | 4.1793 -1.1612 11.3625 828 | -10.1673 -1.1612 15.8667 829 | -3.0190 -1.1962 5.7275 830 | 3.8663 -1.1973 7.4654 831 | 3.4991 -1.1708 8.9451 832 | 3.5177 -1.1628 10.9075 833 | -9.3107 -1.1962 15.4225 834 | 0.3045 -1.2231 5.6482 835 | -7.7873 -1.2077 7.1275 836 | 3.6072 -1.2380 9.0215 837 | 3.4794 -1.2161 10.5798 838 | -10.8287 -1.2312 15.8075 839 | -4.7773 -1.2641 5.7975 840 | -7.7523 -1.2407 7.1975 841 | 3.8181 -1.2654 9.2110 842 | -6.6323 -1.2559 14.4425 843 | -6.5623 -1.2507 16.4375 844 | -4.4973 -1.3012 5.9007 845 | -7.7115 -1.3012 7.4775 846 | 3.9215 -1.3094 9.2822 847 | -6.7723 -1.2670 14.5475 848 | -7.8923 -1.2667 17.2425 849 | 2.1877 -1.3362 6.3755 850 | 8.2427 -1.3362 8.0667 851 | 3.5300 -1.3418 10.4499 852 | -7.9273 -1.3160 16.4375 853 | -1.0202 -1.3712 5.9375 854 | 4.8127 -1.3712 7.6089 855 | 4.1126 -1.3895 9.4578 856 | -8.1373 -1.3378 15.0375 857 | 2.3977 -1.4062 5.6771 858 | 3.9940 -1.3997 6.7303 859 | -7.5423 -1.4062 8.4225 860 | 4.5480 -1.4253 9.9362 861 | -8.6973 -1.3720 16.9625 862 | -4.2810 -1.4412 6.2875 863 | 4.2115 -1.4312 7.8916 864 | 4.2358 -1.4271 9.4409 865 | -8.7379 -1.4437 15.2572 866 | 1.7327 -1.4470 5.8325 867 | -7.2623 -1.4718 7.2675 868 | -3.8314 -1.4762 8.7025 869 | 4.5791 -1.4817 9.9221 870 | -7.4023 -1.4762 16.9475 871 | 7.3778 -1.5112 6.2875 872 | 4.2877 -1.5112 7.3894 873 | 6.5450 -1.5112 9.1575 874 | -9.9922 -1.5112 14.7925 875 | -5.4423 -1.5462 5.8252 876 | -6.8781 -1.5462 6.8125 877 | -7.0873 -1.5442 8.1775 878 | 3.4550 -1.5473 10.2316 879 | -8.9773 -1.5462 17.3937 880 | -4.0688 -1.5812 6.4625 881 | 2.5420 -1.5812 7.6525 882 | -4.8839 -1.5812 9.3675 883 | -7.4023 -1.5757 16.7875 884 | 3.3544 -1.5993 6.0745 885 | 4.0390 -1.6416 7.4829 886 | 4.4058 -1.6203 9.1276 887 | -8.9073 -1.6162 15.2112 888 | -3.4823 -1.6512 5.9645 889 | 2.9577 -1.6512 7.3497 890 | -6.4223 -1.6215 8.8425 891 | -9.8873 -1.6186 14.9325 892 | -3.5173 -1.6862 5.9845 893 | -1.9773 -1.6745 7.1975 894 | 8.1027 -1.6711 8.5975 895 | -8.9773 -1.6862 14.3869 896 | 7.1227 -1.6893 6.0425 897 | 4.2177 -1.7000 7.1975 898 | -4.1204 -1.7213 8.8075 899 | -9.8948 -1.7213 14.6875 900 | 3.3465 -1.7554 6.4148 901 | -6.8166 -1.7562 7.7575 902 | 4.6628 -1.7562 10.2425 903 | 6.8077 -1.7912 5.8694 904 | -6.7023 -1.7912 7.8253 905 | 4.7214 -1.7775 9.5176 906 | -6.4722 -1.8262 6.0775 907 | 5.0927 -1.8262 7.6265 908 | 6.8077 -1.8139 9.1575 909 | 6.5977 -1.8612 5.7761 910 | 7.9007 -1.8612 7.4425 911 | 7.5777 -1.8349 9.1225 912 | 3.2364 -1.8963 5.5875 913 | -1.3123 -1.8683 7.1975 914 | -5.8782 -1.8963 8.8075 915 | -1.4173 -1.9312 5.3817 916 | 7.4027 -1.9301 6.5325 917 | -6.0373 -1.8970 7.8275 918 | -5.4073 -1.9300 9.1575 919 | 4.3227 -1.9331 5.9375 920 | -6.8037 -1.9662 7.1975 921 | -4.1473 -1.9628 8.6325 922 | -5.2673 -2.0012 5.4565 923 | -4.4623 -2.0012 6.5753 924 | 7.8927 -1.9774 7.7925 925 | 4.4353 -2.0012 10.5225 926 | 0.7741 -2.0362 6.1475 927 | -6.7373 -2.0272 7.1625 928 | -5.4773 -2.0035 8.8075 929 | -6.4223 -2.0389 5.6925 930 | -1.4173 -2.0487 6.9525 931 | 6.0868 -2.0712 8.2475 932 | -9.5723 -2.0712 14.3922 933 | -3.8323 -2.1063 6.2726 934 | 5.3377 -2.1060 7.5475 935 | 7.3677 -2.0724 8.7375 936 | -6.5273 -2.1335 5.7975 937 | -2.8873 -2.1412 6.9759 938 | -4.2873 -2.1362 8.0025 939 | -9.3273 -2.1374 14.6175 940 | 1.8727 -2.1762 6.3909 941 | 5.5827 -2.1525 7.7225 942 | -8.7119 -2.1762 14.0925 943 | 6.6677 -2.2110 6.0775 944 | 7.6006 -2.2112 7.3025 945 | -9.1228 -2.2112 14.1975 946 | 6.8022 -2.2462 6.1825 947 | -4.1823 -2.2462 7.7337 948 | -5.1973 -2.2715 5.3775 949 | 0.7527 -2.2813 6.3278 950 | -5.6523 -2.2551 7.8625 951 | 5.5477 -2.2986 5.9375 952 | -6.3873 -2.3162 7.2403 953 | 3.9027 -2.3055 10.5575 954 | 0.7463 -2.3512 6.2875 955 | -5.8273 -2.3450 7.6175 956 | 3.1327 -2.3862 5.5978 957 | -2.7266 -2.3862 6.7425 958 | 4.4852 -2.3862 10.2425 959 | -2.4323 -2.4202 6.4625 960 | 3.1875 -2.4212 7.9325 961 | 0.7527 -2.4562 6.1127 962 | 6.0027 -2.4447 7.4775 963 | -4.7773 -2.4913 5.6566 964 | 5.5127 -2.4913 6.8498 965 | 4.0777 -2.4913 10.4302 966 | -3.5173 -2.5262 6.4304 967 | -4.1123 -2.5262 7.6707 968 | -1.9773 -2.5435 5.9025 969 | 3.6927 -2.5288 7.1275 970 | 1.1377 -2.5910 5.7625 971 | 3.4127 -2.5898 8.9125 972 | -4.4973 -2.6137 7.8625 973 | 3.3427 -2.6663 7.3341 974 | -6.4223 -2.6739 7.1975 975 | -3.8323 -2.7362 7.0894 976 | -3.9723 -2.7544 7.4075 977 | 3.4827 -2.8055 7.6875 978 | -4.2873 -2.8146 7.7225 979 | 4.6027 -2.8453 9.0175 980 | -4.5323 -2.9462 5.6832 981 | 3.7977 -2.9812 8.1784 982 | -6.4573 -3.0232 5.4475 983 | -4.3223 -3.0586 6.9875 984 | -4.9523 -3.1212 7.6840 985 | -6.4573 -3.1912 6.9542 986 | -4.5648 -3.2612 6.9175 987 | -4.5673 -3.3051 5.5875 988 | -4.9173 -3.3558 6.7075 989 | -5.1623 -3.3989 7.5125 990 | -5.1973 -3.4713 7.2970 991 | -5.5823 -3.5550 5.6925 992 | -5.5064 -3.6463 7.4075 993 | -5.4073 -3.7310 6.3925 994 | -6.4246 -3.8562 6.7425 995 | -6.2769 -4.1012 7.1625 996 | -2.2749 0.9372 14.7241 997 | 3.6270 0.0026 5.9452 998 | -1.7673 -0.8813 5.5700 999 | 4.0616 -1.4888 7.9442 1000 | 4.3770 -2.0292 7.9644 1001 | -------------------------------------------------------------------------------- /data/pointclouds/dragon_sparse100_part2.xyz: -------------------------------------------------------------------------------- 1 | 3.3468 5.3526 6.4960 2 | 4.0284 5.2480 6.4929 3 | 2.8582 5.1195 7.2321 4 | 2.6305 5.0189 7.3083 5 | 3.9529 5.0051 6.2461 6 | 2.7207 4.8562 6.9026 7 | 3.3690 4.8061 7.6291 8 | -1.8415 4.2921 18.3071 9 | 2.9414 4.6916 6.9494 10 | 3.8201 4.6978 7.1911 11 | 3.0568 4.6163 8.1621 12 | 3.0976 4.5694 8.2599 13 | 2.8979 4.5236 8.2711 14 | -3.5650 4.1815 6.6386 15 | -1.6311 4.0949 16.9683 16 | -2.8529 4.1855 6.9599 17 | -2.4303 4.0051 17.0447 18 | 3.0975 4.4526 7.0412 19 | -2.8399 3.9441 17.2802 20 | 4.5426 4.4922 7.0923 21 | -3.0738 3.9156 17.5760 22 | -2.1882 4.0982 7.4255 23 | -2.1977 3.9027 17.5388 24 | -2.5431 4.0750 7.6477 25 | -2.8604 3.8276 17.8122 26 | 4.3060 4.3872 7.4139 27 | -3.1866 3.8123 17.1928 28 | 3.0101 4.2712 7.2820 29 | -3.0199 3.7925 16.9065 30 | -3.3534 3.8999 7.2676 31 | -3.1194 3.7249 16.9788 32 | -7.9576 3.6181 7.5617 33 | -3.5035 3.6521 17.9367 34 | 4.5380 4.2522 6.8077 35 | -3.0507 3.6982 15.8551 36 | -2.3719 3.8620 6.4471 37 | 3.9399 4.2011 7.7037 38 | -2.0432 3.6694 17.3255 39 | 4.5058 4.1809 6.7802 40 | -3.0911 3.6135 15.5646 41 | -3.9948 3.5238 18.7572 42 | -7.6679 3.4916 7.6331 43 | -2.1129 3.6193 16.1012 44 | -4.3228 3.6588 6.2290 45 | -1.9663 3.7859 7.6575 46 | -2.1511 3.7545 8.3640 47 | -3.5729 3.4798 17.6909 48 | -8.1655 3.4011 7.3419 49 | 3.9906 4.0387 7.9092 50 | -2.2835 3.5546 15.7272 51 | -8.3227 3.3692 6.7485 52 | -1.7081 3.6949 7.8921 53 | 1.8369 3.7695 14.2846 54 | -3.9796 3.3807 17.9496 55 | 4.7632 4.0173 6.8758 56 | -2.3534 3.6154 8.3844 57 | 1.4005 3.7353 13.7738 58 | 2.6021 3.7716 15.1335 59 | -3.3829 3.3652 18.5579 60 | -4.8620 3.4947 7.6485 61 | 3.7449 3.9246 8.7565 62 | 1.7482 3.7179 13.6563 63 | 3.2784 3.7404 15.3784 64 | -2.3847 3.5822 6.3803 65 | 2.5380 3.8239 7.8464 66 | 4.4578 3.8929 9.0463 67 | 0.1826 3.6253 11.8179 68 | 4.6525 3.8210 13.6267 69 | 4.0377 3.7836 15.0836 70 | -3.9889 3.2971 18.5779 71 | 5.0648 3.9189 7.3442 72 | 3.6864 3.8410 8.9672 73 | -0.3585 3.5613 11.2753 74 | 5.3387 3.8216 13.1824 75 | 4.6847 3.7950 14.5358 76 | -4.2950 3.2285 17.7198 77 | -8.0511 3.2108 7.4816 78 | -1.6061 3.5064 8.7960 79 | -0.4708 3.5391 11.0336 80 | 5.2787 3.8218 12.4490 81 | 1.1600 3.5385 14.6427 82 | -4.0469 3.2020 17.9478 83 | -7.6512 3.1771 7.6321 84 | -6.3128 3.2556 8.9560 85 | 4.9811 3.7770 10.8473 86 | 5.4487 3.7738 13.2478 87 | 4.1590 3.6780 15.3928 88 | -2.6738 3.4322 6.0999 89 | -2.7733 3.3892 8.0582 90 | -0.8522 3.4525 9.9940 91 | -0.4976 3.4630 12.1891 92 | 1.4238 3.4736 15.0822 93 | -3.4576 3.1621 18.5220 94 | 4.6683 3.7492 7.7929 95 | 2.6972 3.6085 9.7333 96 | 1.4783 3.5070 12.6112 97 | -3.3591 3.1846 15.2656 98 | -3.5199 3.1273 18.6987 99 | -1.4794 3.3863 8.0889 100 | -1.3723 3.3562 9.9410 101 | -0.4791 3.3834 12.6074 102 | -3.6610 3.1315 15.3761 103 | -2.5160 3.3626 6.3033 104 | -2.4713 3.2906 8.5422 105 | -1.3749 3.3558 9.9411 106 | -0.8082 3.3092 12.0954 107 | -3.9854 3.1012 15.2819 108 | -4.3044 3.0284 18.1639 109 | 3.9848 3.6218 7.0890 110 | -1.3425 3.3258 8.7836 111 | 0.4759 3.3858 10.7877 112 | 5.7662 3.5847 14.0390 113 | -4.5257 2.9920 17.7857 114 | -8.0266 2.9665 7.6097 115 | -0.6663 3.3020 9.2149 116 | 0.8478 3.3585 11.3697 117 | 5.1390 3.5104 15.0754 118 | -0.2318 3.1268 19.4819 119 | -6.2206 3.0012 8.1777 120 | 0.0321 3.3115 9.9963 121 | 2.0245 3.3363 12.9357 122 | 4.7318 3.4647 15.4041 123 | 0.2474 3.1123 19.7227 124 | -6.1901 2.9980 8.0365 125 | -1.9214 3.1797 10.0972 126 | 6.1276 3.5179 13.2196 127 | -2.4311 2.9899 16.9770 128 | -5.6001 2.9846 6.8247 129 | 5.0807 3.5395 8.2477 130 | 5.4503 3.5124 10.8263 131 | -3.0811 2.9739 14.8628 132 | -4.7770 2.8250 17.3362 133 | -6.0115 2.9244 7.0132 134 | -0.8113 3.1919 8.7277 135 | -1.4583 3.1129 11.2358 136 | 0.0924 3.1043 14.2638 137 | -4.9617 2.7876 16.9567 138 | 5.5483 3.5296 6.5149 139 | -1.2832 3.1448 8.1829 140 | -2.0493 3.0346 10.2347 141 | 3.5869 3.2976 13.4446 142 | -2.2657 2.9149 16.0592 143 | 0.1048 2.9591 20.0052 144 | -3.5210 2.9638 8.0952 145 | 2.3051 3.2714 9.7411 146 | 3.3090 3.2291 13.4181 147 | -4.6845 2.7343 16.8388 148 | -8.7855 2.6775 6.8256 149 | -3.5383 2.9338 8.5732 150 | 2.8647 3.2144 10.6312 151 | -3.8048 2.7837 14.8497 152 | -2.3821 2.8173 16.9722 153 | -8.7325 2.6607 6.9985 154 | -0.5968 3.0641 8.6479 155 | 5.6337 3.3550 10.8172 156 | -2.5597 2.8238 14.4917 157 | -4.7194 2.6881 16.7714 158 | -2.9869 2.9231 6.2072 159 | -6.5500 2.6956 8.3261 160 | -1.8861 2.8937 10.7215 161 | -2.8891 2.7776 14.0147 162 | 4.4148 3.1246 15.8645 163 | -0.3798 2.7973 19.8092 164 | 5.4125 3.3063 7.3286 165 | -2.3220 2.8463 10.1727 166 | -3.6714 2.7276 13.6181 167 | 2.0419 2.9632 15.9622 168 | -0.9431 2.7582 19.0146 169 | -8.5780 2.5447 7.2363 170 | -7.0333 2.5943 9.4249 171 | 6.3057 3.2290 11.9474 172 | -4.3909 2.6104 14.9655 173 | -2.8978 2.6314 17.9327 174 | -2.4396 2.8371 6.6997 175 | -0.7069 2.9320 8.2992 176 | 1.0681 2.9619 11.0398 177 | -4.1709 2.5998 14.2988 178 | -5.6438 2.4697 17.0451 179 | -8.5510 2.4781 6.8955 180 | -0.5978 2.8787 8.3295 181 | -2.0898 2.7468 10.6560 182 | -2.8932 2.6427 13.7296 183 | 2.2254 2.8848 16.0769 184 | -1.6085 2.6001 19.4279 185 | -8.2738 2.4445 7.5742 186 | 5.4139 3.1307 10.1905 187 | 6.3816 3.1128 13.8692 188 | -2.0577 2.5946 16.6768 189 | -2.9967 2.7082 6.4138 190 | 5.4964 3.1502 7.4909 191 | 3.0678 2.9691 11.0752 192 | -2.4625 2.5880 14.0989 193 | -2.0170 2.5647 16.6398 194 | -7.8860 2.4105 6.7514 195 | -0.7798 2.7596 7.9494 196 | 3.1198 2.9016 11.1773 197 | -4.4023 2.4446 14.4443 198 | -5.2011 2.3624 16.5377 199 | -3.5276 2.6121 6.3217 200 | -0.7433 2.7318 7.9467 201 | 2.9296 2.8645 10.9731 202 | -1.9410 2.5631 14.7457 203 | -1.8752 2.5092 16.5989 204 | -1.3179 2.4733 19.5231 205 | 1.8054 2.8328 7.5442 206 | -1.7006 2.5726 11.5165 207 | -4.9974 2.3310 14.9427 208 | -1.4140 2.5126 16.7580 209 | -4.1508 2.5079 6.3963 210 | -0.7420 2.6586 7.8403 211 | 3.4529 2.8047 11.8295 212 | -5.3494 2.2983 14.9781 213 | 3.5737 2.7219 16.2851 214 | -2.4801 2.3649 19.2095 215 | 5.9102 2.9877 7.0306 216 | -2.2538 2.5109 10.6226 217 | 6.4977 2.8800 14.2113 218 | 1.3228 2.5769 15.8701 219 | -5.7343 2.1646 18.0814 220 | 6.3360 3.0221 6.1984 221 | 0.1603 2.6160 8.8588 222 | -3.9413 2.3351 12.2897 223 | -4.5049 2.2541 14.9087 224 | 3.1134 2.6268 16.3216 225 | -2.6777 2.2828 18.4281 226 | 3.9636 2.8303 6.2610 227 | 4.8925 2.8246 9.0825 228 | -5.2076 2.2557 12.0523 229 | -5.2628 2.1693 14.9718 230 | -5.8799 2.1141 16.6618 231 | -2.8825 2.2218 19.2210 232 | 6.1512 2.8989 6.8331 233 | -6.4842 2.1998 10.5197 234 | -5.2983 2.1735 13.3500 235 | -1.4482 2.3277 15.8102 236 | -6.1033 2.0540 17.3691 237 | 3.2590 2.7373 6.0206 238 | -6.9278 2.1874 7.7679 239 | -6.4094 2.1538 10.5864 240 | -0.9839 2.3673 13.2027 241 | 0.2949 2.4145 15.2955 242 | 2.1912 2.4951 16.5267 243 | -3.5379 2.1339 18.6820 244 | 3.7869 2.7349 6.0722 245 | 5.8458 2.7998 7.5076 246 | -5.9484 2.1383 10.7101 247 | -3.4694 2.2159 12.4813 248 | -4.5508 2.1011 14.9072 249 | 1.9112 2.4454 16.4655 250 | -5.6798 2.0059 18.4043 251 | 3.0186 2.6454 6.0274 252 | -6.6670 2.1169 8.1078 253 | -5.7695 2.1115 10.7734 254 | -2.9665 2.1981 12.9538 255 | 6.2336 2.6752 15.0226 256 | 2.4089 2.4195 16.6228 257 | -3.4361 2.0477 19.4778 258 | 4.8877 2.7004 6.4217 259 | -4.8203 2.1260 9.8326 260 | -5.6940 2.0549 12.9064 261 | -5.5272 1.9604 15.0020 262 | 1.2459 2.3191 16.3004 263 | -5.6274 1.9165 18.5060 264 | -1.9350 2.3090 6.3697 265 | -0.2263 2.3652 8.0974 266 | -6.4334 1.9792 11.6700 267 | -0.9081 2.2242 13.6529 268 | 0.0660 2.2634 15.5461 269 | -1.6352 2.1451 16.8994 270 | -2.2162 2.2628 6.1837 271 | 4.9012 2.5819 8.9729 272 | 6.4430 2.6150 11.4415 273 | 6.8847 2.5999 13.4250 274 | 0.2191 2.2043 15.8328 275 | 2.7337 2.3186 16.7373 276 | -2.6032 2.2160 6.0762 277 | 1.6450 2.4038 7.5415 278 | -6.7643 1.8889 11.3997 279 | -1.1318 2.1641 13.1693 280 | -5.1449 1.9065 15.2591 281 | -6.5919 1.7894 17.0266 282 | -2.7421 2.1679 6.0408 283 | -0.5186 2.2539 7.6226 284 | 3.0858 2.3702 11.3794 285 | -5.5208 1.8759 13.6328 286 | -0.4677 2.1126 15.0876 287 | -1.7798 2.0129 16.6920 288 | -3.4883 1.8677 19.7264 289 | 6.1970 2.5813 7.0712 290 | -2.2548 2.0634 10.9651 291 | 3.3514 2.3203 12.8754 292 | -5.9563 1.7948 14.8375 293 | 1.6072 2.1838 16.4015 294 | -3.7511 1.8267 19.1744 295 | -8.2966 1.8083 7.1436 296 | 5.8051 2.4638 10.3403 297 | 6.8593 2.4922 12.5107 298 | -1.7036 1.9859 14.6573 299 | 1.6752 2.1565 16.2936 300 | -6.2615 1.6976 18.3491 301 | 6.6737 2.5479 6.4585 302 | -2.3595 1.9905 10.8268 303 | -2.3318 1.9651 13.0009 304 | -1.6967 1.9557 14.7966 305 | 1.8185 2.1174 16.3229 306 | -6.1735 1.6437 18.4502 307 | -1.2408 2.0955 6.7620 308 | -7.3209 1.6939 10.9091 309 | 3.4365 2.2210 12.8006 310 | -1.7321 1.9174 14.7272 311 | 1.5685 2.0732 16.1207 312 | -6.6291 1.5872 18.3250 313 | -7.3636 1.7353 6.8295 314 | 1.1175 2.1220 10.2018 315 | -2.5682 1.8722 12.7578 316 | 8.4521 2.4614 13.9256 317 | 5.8946 2.2579 15.7468 318 | -6.8831 1.5596 17.2476 319 | 4.7549 2.3546 6.1018 320 | 5.0300 2.3030 9.2437 321 | -2.5329 1.8683 12.7577 322 | 7.7228 2.3485 14.1943 323 | 1.9234 2.0065 16.1772 324 | -6.6408 1.5178 18.2542 325 | -7.7497 1.6379 7.1916 326 | -7.4565 1.5973 10.8934 327 | 7.3872 2.3528 12.3497 328 | 8.5354 2.3568 14.1490 329 | 1.0376 1.9330 15.7595 330 | -6.8451 1.4892 17.3616 331 | -1.3785 1.9497 6.5191 332 | -2.7870 1.8023 10.3374 333 | -1.7378 1.8069 12.7727 334 | -0.9093 1.8286 14.2886 335 | 5.8618 2.1803 15.6924 336 | -6.4165 1.5057 17.6157 337 | 5.3220 2.2727 6.1501 338 | -2.8210 1.7665 10.3142 339 | 7.0678 2.2499 12.0762 340 | 7.3086 2.2468 13.9968 341 | 6.1396 2.1361 15.5419 342 | -6.2804 1.4572 18.4507 343 | -1.3086 1.9152 6.5511 344 | -2.6315 1.7355 10.5872 345 | 8.0588 2.2627 12.2896 346 | 6.9156 2.1629 14.3594 347 | 1.5044 1.8488 15.9471 348 | -6.1350 1.3992 18.5092 349 | -7.4375 1.5137 7.2135 350 | -3.6094 1.6312 11.6703 351 | -1.2779 1.7207 13.5886 352 | -5.8413 1.4438 15.2995 353 | -7.8562 1.2984 17.2389 354 | 5.5322 2.1815 6.0007 355 | -4.4039 1.5754 10.4362 356 | 8.1066 2.1958 12.2518 357 | 7.0407 2.1255 14.1792 358 | 4.7268 1.9468 15.9828 359 | -3.0536 1.5040 19.5647 360 | 0.4518 1.8269 8.7648 361 | 3.0807 1.9289 11.3838 362 | -1.1996 1.6787 13.5135 363 | -1.6983 1.5899 15.2101 364 | -7.9670 1.2237 17.1745 365 | 2.0170 1.9175 6.5051 366 | 6.0405 2.0533 10.3950 367 | -2.5842 1.5684 12.7462 368 | 7.4696 2.0527 14.3049 369 | -6.9301 1.2549 16.5601 370 | -4.5996 1.5430 6.1320 371 | 5.3491 1.9971 9.6112 372 | -6.9369 1.3015 12.3064 373 | 9.1623 2.1398 13.6850 374 | 5.6859 1.9028 15.4135 375 | -3.7299 1.3399 19.0251 376 | -7.9680 1.2807 8.7653 377 | 6.7540 2.0041 11.2449 378 | 8.4368 2.0613 12.8511 379 | -4.6720 1.3320 15.0690 380 | -6.1152 1.2229 16.7946 381 | -6.5747 1.3614 6.5509 382 | 2.5517 1.7701 10.4923 383 | -2.8605 1.4435 12.3538 384 | 9.3378 2.0597 13.5631 385 | 0.5845 1.5682 15.2722 386 | -5.8361 1.1660 18.6857 387 | 4.9828 1.8894 8.7478 388 | 3.0520 1.7470 11.2672 389 | 2.7815 1.6913 13.0386 390 | 9.2334 2.0198 14.5561 391 | 2.6792 1.6443 16.1445 392 | -2.4628 1.5169 6.0204 393 | -8.0556 1.1628 9.1905 394 | -7.5090 1.1465 11.5179 395 | 2.4269 1.6414 12.8445 396 | 7.5503 1.8809 14.3451 397 | -1.7792 1.3512 16.4702 398 | -2.7357 1.4648 6.1641 399 | -8.0703 1.1297 9.6457 400 | 7.8261 1.9420 11.2063 401 | 6.8421 1.8455 13.0604 402 | -7.2069 1.0750 15.3590 403 | -1.9627 1.2915 17.2812 404 | 7.3761 1.9579 6.2485 405 | -3.7803 1.2938 10.3744 406 | 8.1149 1.9147 11.4059 407 | 9.5859 1.9416 13.4566 408 | 9.1441 1.8853 14.8131 409 | -8.4362 0.9104 17.6057 410 | 7.4437 1.9286 6.1291 411 | 5.7160 1.7686 9.7322 412 | -3.3464 1.2599 11.5676 413 | 9.0797 1.8834 12.9175 414 | 9.1112 1.8592 14.8378 415 | -1.6114 1.2404 17.2190 416 | -3.6427 1.3330 6.4132 417 | -3.6913 1.2264 10.4752 418 | -1.7201 1.2993 12.0519 419 | 9.6309 1.8882 13.6643 420 | 8.3371 1.7692 15.0034 421 | -8.3643 0.8394 17.8472 422 | -0.1656 1.4310 7.6236 423 | 3.1502 1.5353 11.2224 424 | -1.0757 1.2761 13.1869 425 | -5.8741 0.9854 15.2232 426 | -6.7951 0.9051 16.8900 427 | -6.0120 1.1169 6.2143 428 | 1.9227 1.4768 9.1044 429 | -7.4619 0.9339 11.7647 430 | 7.1961 1.6791 12.9400 431 | 9.6089 1.7740 14.5737 432 | -5.1864 0.9719 16.3946 433 | -1.2066 1.1483 17.6376 434 | 7.3338 1.7895 5.7728 435 | 0.7590 1.3769 9.3067 436 | -1.9461 1.1943 11.4287 437 | 3.0108 1.4304 13.1870 438 | -6.2576 0.8966 15.1519 439 | -1.2554 1.1716 16.2387 440 | -1.9653 1.0687 17.8908 441 | 2.1773 1.4746 6.2754 442 | 5.9145 1.5998 9.9361 443 | -3.2503 1.1119 12.1391 444 | 9.6915 1.7357 13.1462 445 | -5.2030 0.9149 15.2535 446 | 3.7062 1.3671 16.0046 447 | -1.0500 1.0847 18.0163 448 | 5.8138 1.6074 7.4529 449 | 7.8918 1.6831 10.6741 450 | 8.1786 1.6520 12.8702 451 | -7.2070 0.7817 14.8990 452 | 8.5803 1.6005 15.3220 453 | -0.8111 1.0738 17.6308 454 | 6.8643 1.6324 7.1920 455 | 1.2497 1.2727 10.6537 456 | 6.5335 1.5479 11.7700 457 | 7.6330 1.5727 13.2031 458 | 7.7552 1.5347 14.6748 459 | -5.8163 0.8095 16.1709 460 | -0.2386 1.0501 18.0925 461 | -7.9380 0.8341 7.9197 462 | 5.8911 1.4867 10.2852 463 | -3.5063 0.9787 11.6203 464 | -5.9777 0.8011 13.5950 465 | 9.6256 1.6024 14.4301 466 | -0.5963 1.0368 15.6152 467 | -8.8212 0.6038 17.6839 468 | 7.5425 1.6115 6.4752 469 | 5.6647 1.4585 9.8023 470 | 6.0429 1.4467 10.9447 471 | 3.8701 1.2971 12.8044 472 | 10.2526 1.6151 13.9881 473 | -1.3856 0.9733 15.5532 474 | -1.0324 0.9536 17.2999 475 | 7.5947 1.5900 5.9165 476 | 5.2067 1.3966 9.6420 477 | 6.9520 1.4528 11.6101 478 | -5.5644 0.7474 13.8598 479 | -5.5779 0.7196 15.2685 480 | 4.2123 1.2221 15.8034 481 | -7.8629 0.5484 17.9359 482 | 6.8807 1.4880 7.4477 483 | -2.4455 0.9333 10.5005 484 | -3.2657 0.8736 12.3457 485 | 9.2323 1.4960 13.7064 486 | -1.6086 0.8965 15.3611 487 | -0.9298 0.9115 16.1260 488 | -2.9489 0.7619 18.3941 489 | 5.8496 1.3969 7.5530 490 | -3.5690 0.8467 10.4994 491 | 6.5279 1.3403 12.3270 492 | -4.7234 0.7064 14.6354 493 | -6.5893 0.5865 15.7843 494 | -6.8497 0.5315 17.9290 495 | 2.0783 1.1835 6.5602 496 | 4.9967 1.3022 9.5076 497 | -3.3718 0.8025 12.2080 498 | 9.7300 1.4443 13.8225 499 | -1.2970 0.8414 15.5158 500 | -9.0829 0.4090 17.9348 501 | 4.0409 1.2721 6.0690 502 | 5.2275 1.2695 8.8335 503 | -3.8141 0.7447 11.4862 504 | 2.5465 1.0417 13.3641 505 | -8.3642 0.4317 15.3532 506 | 8.7735 1.3588 15.4713 507 | -8.3401 0.3805 18.0761 508 | 4.5722 1.2657 6.0306 509 | 5.1895 1.2324 8.8342 510 | 5.7438 1.2233 10.8112 511 | -5.7826 0.5627 13.7591 512 | 7.9089 1.2946 14.6948 513 | -0.7281 0.7896 15.7232 514 | -0.6863 0.7596 17.8929 515 | -1.0473 0.9160 6.4890 516 | 2.6280 1.0733 9.6214 517 | -1.4076 0.7895 12.0691 518 | 8.4180 1.2876 14.1865 519 | 8.5239 1.2611 15.1981 520 | -6.1598 0.4403 17.1527 521 | -2.7579 0.5994 18.7533 522 | 6.4153 1.2766 7.2506 523 | -8.0352 0.4326 10.7532 524 | -6.4673 0.4699 13.0809 525 | -2.2256 0.6550 15.0026 526 | -7.8169 0.3823 15.8892 527 | -0.9162 0.6814 17.1990 528 | -2.5754 0.5770 18.9009 529 | 7.4517 1.2790 7.1097 530 | 2.8472 1.0149 9.7878 531 | -3.7875 0.6018 11.6936 532 | 3.7146 0.9729 13.5747 533 | 8.8589 1.2130 14.6602 534 | 3.1256 0.8963 15.7306 535 | -8.0102 0.2644 18.3152 536 | -4.2834 0.6414 6.4869 537 | 2.7720 0.9525 9.5442 538 | -1.5989 0.6980 11.5838 539 | -2.4970 0.6189 13.9256 540 | 9.8795 1.2233 14.7825 541 | -1.1934 0.6342 16.1921 542 | -7.5515 0.2686 18.4043 543 | 3.8112 1.0113 6.1084 544 | 5.2791 1.0695 8.4429 545 | 6.9005 1.1132 10.7818 546 | 2.2746 0.8430 13.3075 547 | -8.9149 0.1937 15.2982 548 | 3.7539 0.8704 15.6031 549 | -8.3932 0.1643 18.2422 550 | 3.7199 1.0018 6.0908 551 | 5.7590 1.0710 7.8442 552 | -2.1400 0.6204 10.7568 553 | 1.6593 0.7641 12.6229 554 | -4.4180 0.4344 14.9002 555 | -7.5647 0.2202 15.7056 556 | -7.9448 0.1818 17.0154 557 | -4.3192 0.3341 18.6805 558 | -0.6707 0.7166 6.9396 559 | 4.6102 0.9429 9.5499 560 | 1.2745 0.7268 11.6941 561 | -5.0330 0.3497 14.1145 562 | 9.6394 1.1148 14.7713 563 | -8.5592 0.1282 16.0202 564 | -8.3153 0.0958 18.3616 565 | 2.4176 0.8583 6.1924 566 | 2.0131 0.7857 8.0350 567 | -2.2448 0.5265 10.5575 568 | 1.7746 0.7298 12.8676 569 | 1.4640 0.6392 14.9369 570 | -7.8866 0.1458 15.9498 571 | -6.8127 0.1413 18.2750 572 | -1.4276 0.6214 6.1880 573 | 4.9287 0.8751 7.7313 574 | 4.7226 0.8806 10.0703 575 | 4.0900 0.8313 12.0180 576 | 2.7940 0.6970 13.9173 577 | -4.8510 0.2662 15.3102 578 | -1.2407 0.4504 16.5758 579 | -5.9212 0.1553 18.7307 580 | 2.2960 0.7770 6.6155 581 | 5.0111 0.8499 7.9971 582 | 7.0635 0.9423 10.7952 583 | -0.3386 0.5316 13.3233 584 | -6.0100 0.1741 15.1164 585 | -4.8084 0.2310 16.4097 586 | -3.7559 0.2266 18.5162 587 | 2.3955 0.7477 6.4014 588 | 5.0310 0.8449 7.9930 589 | 0.8653 0.5853 10.6552 590 | -6.6099 0.1502 12.9077 591 | 0.5704 0.5312 14.2723 592 | -9.1055 -0.0118 15.5815 593 | -8.5851 -0.0405 17.4338 594 | -2.8646 0.2294 18.9755 595 | 4.2347 0.8062 6.7543 596 | 0.2150 0.5556 8.6108 597 | 4.8189 0.7574 10.6496 598 | -6.1398 0.1323 13.2971 599 | 1.4845 0.5068 14.5902 600 | 3.8536 0.6337 15.0701 601 | -6.7049 0.0106 17.3533 602 | -2.3373 0.2209 19.0347 603 | 4.9667 0.8210 7.3192 604 | -8.2024 0.0585 9.7017 605 | 4.7536 0.7194 10.7319 606 | -0.3749 0.4189 13.1124 607 | 2.8507 0.5790 14.3686 608 | 3.5677 0.6059 14.8694 609 | -4.7418 0.0917 16.3301 610 | -2.6319 0.1955 18.5815 611 | -1.1634 0.4589 6.4856 612 | 0.2045 0.5179 8.6455 613 | 4.3342 0.6612 10.6844 614 | -0.5651 0.3900 12.6282 615 | 2.1120 0.4783 14.1475 616 | -2.1838 0.2304 15.3140 617 | -6.9400 -0.0500 17.4141 618 | -6.4853 0.1449 6.2510 619 | 6.2953 0.7870 7.7019 620 | 8.5209 0.8714 9.3421 621 | -3.7658 0.1858 12.0359 622 | 4.7563 0.5930 13.7068 623 | -6.0696 -0.0049 15.1495 624 | -5.3496 0.0296 16.2856 625 | -2.9850 0.1136 18.3822 626 | 3.6746 0.6506 6.1232 627 | 5.1783 0.6691 8.0438 628 | -7.9914 -0.0536 10.6381 629 | 5.3403 0.6177 12.3559 630 | 4.9637 0.5767 13.5942 631 | -9.4842 -0.2069 15.4862 632 | -8.5317 -0.2181 17.6970 633 | 3.8077 0.6446 5.9207 634 | 4.6650 0.6425 7.4669 635 | 8.4360 0.8043 8.9585 636 | 7.3090 0.6945 11.5877 637 | -4.3841 0.0478 14.2617 638 | -8.0860 -0.1932 15.8012 639 | -2.3111 0.0762 17.5165 640 | -2.9465 0.2262 6.1935 641 | 2.1225 0.4718 7.2242 642 | 7.8654 0.7798 8.4876 643 | 8.5438 0.7262 11.4753 644 | -9.6317 -0.2964 15.1327 645 | -5.0922 -0.0822 16.1930 646 | -3.0886 -0.0134 18.2315 647 | 7.3273 0.7331 5.9965 648 | 4.7883 0.6092 7.6447 649 | 7.0693 0.6496 9.6238 650 | 0.0121 0.2510 12.8858 651 | -7.9465 -0.2161 15.7996 652 | -6.0832 -0.1693 17.1527 653 | -5.8152 0.0067 6.1469 654 | 4.3387 0.5323 6.8877 655 | 7.7318 0.6707 8.5146 656 | 7.2294 0.5952 11.0635 657 | -9.5939 -0.3641 15.1082 658 | -4.4588 -0.1437 16.4637 659 | -3.2174 -0.0913 18.2817 660 | 7.3328 0.6650 6.0523 661 | -0.1509 0.2523 8.0929 662 | -2.0980 0.0837 10.4347 663 | -3.8517 -0.0642 14.2762 664 | -8.8683 -0.3944 16.2929 665 | -3.7784 -0.1570 18.3500 666 | -0.9298 0.1794 6.8228 667 | 8.2804 0.6389 8.0153 668 | -7.8120 -0.2607 10.9505 669 | -5.3435 -0.1475 13.5913 670 | -9.0290 -0.4181 16.1672 671 | -3.3291 -0.1645 18.1442 672 | -1.5750 0.1220 6.2319 673 | 1.9358 0.2728 7.9503 674 | -1.5566 0.0360 10.7652 675 | -2.9932 -0.1313 14.8265 676 | -5.5680 -0.2447 16.1194 677 | -8.5990 -0.4771 18.2177 678 | -3.3770 -0.0059 6.2658 679 | 8.2340 0.5719 7.7355 680 | -3.9804 -0.1195 10.4052 681 | -5.4490 -0.2285 13.4535 682 | -5.4950 -0.3079 16.0658 683 | -8.7697 -0.5258 18.4680 684 | -3.4779 -0.0486 6.2951 685 | -0.4304 0.0813 7.8194 686 | 7.0614 0.4287 10.1558 687 | -5.5918 -0.2688 13.3176 688 | -8.9870 -0.5285 16.2002 689 | -8.7660 -0.5617 18.5211 690 | 1.1960 0.1727 6.2739 691 | 7.2830 0.4401 8.3619 692 | 0.2028 0.0197 10.9136 693 | -8.2916 -0.5047 15.0284 694 | -3.9415 -0.2895 16.7985 695 | 3.1049 0.2345 5.8369 696 | 1.7479 0.1551 6.9007 697 | 0.0242 0.0109 9.0633 698 | -0.3008 -0.0342 11.4907 699 | -7.6959 -0.5275 16.0110 700 | -8.4953 -0.6091 18.0717 701 | 1.2488 0.0943 6.2549 702 | 6.4749 0.3503 8.1784 703 | -3.9410 -0.2560 10.3196 704 | -4.0048 -0.2928 13.5420 705 | -3.4588 -0.3424 16.1141 706 | -7.5885 -0.6151 19.0338 707 | 2.0167 0.0777 6.8059 708 | 7.0581 0.3467 8.8235 709 | -7.1000 -0.4877 11.9376 710 | -9.0167 -0.6691 16.1387 711 | -4.8394 -0.4933 18.3663 712 | 2.0177 0.0798 6.6540 713 | 7.0160 0.3012 8.5440 714 | 7.5127 0.2552 11.2929 715 | -5.7158 -0.5242 15.9629 716 | -6.6732 -0.6192 18.0971 717 | 4.7110 0.1689 6.4359 718 | 3.7041 0.0707 8.6906 719 | 7.5621 0.2226 11.2906 720 | -9.0137 -0.7096 16.1616 721 | -4.6715 -0.5530 18.2812 722 | 4.7146 0.1514 6.4597 723 | 6.5725 0.1824 8.8726 724 | -6.4443 -0.5434 12.5720 725 | -8.8295 -0.7474 16.3646 726 | -2.5077 -0.2735 6.0325 727 | -0.5109 -0.2090 8.1324 728 | -1.1705 -0.2516 10.3264 729 | -5.2937 -0.5996 15.3861 730 | -8.3460 -0.8122 18.1067 731 | -1.5446 -0.2431 6.5567 732 | 3.4729 -0.0527 9.0118 733 | 4.3295 -0.1056 12.6120 734 | -8.8218 -0.8401 16.4461 735 | -8.5273 -0.8714 18.8691 736 | 2.8326 -0.0772 6.7220 737 | -0.4859 -0.3093 9.7426 738 | 4.3575 -0.1136 12.8303 739 | -4.0029 -0.6189 17.2141 740 | 6.8590 0.1445 5.7446 741 | -7.7894 -0.6886 7.8529 742 | -1.9828 -0.3967 9.9319 743 | -4.0295 -0.6388 15.1644 744 | -4.0339 -0.6742 17.2492 745 | -6.3358 -0.6205 6.3599 746 | -0.5509 -0.3591 8.5165 747 | 8.8124 0.0929 10.5127 748 | -9.2719 -0.9167 15.4664 749 | -4.6798 -0.7527 17.7257 750 | 4.2175 -0.0495 6.0922 751 | 3.9429 -0.1598 8.5732 752 | 7.5721 -0.0093 11.0060 753 | -4.4642 -0.7403 15.8356 754 | -7.2757 -0.9412 18.6187 755 | 4.7211 -0.1394 6.7569 756 | -1.0713 -0.4811 9.7917 757 | -4.2231 -0.7531 15.0757 758 | -5.4419 -0.8457 16.8253 759 | -1.9589 -0.4963 6.3529 760 | 3.9963 -0.2284 8.6387 761 | -6.7307 -0.8333 11.9465 762 | -9.2822 -1.0653 15.9637 763 | -7.3241 -1.0139 18.6191 764 | -0.9568 -0.4691 6.9876 765 | -0.8869 -0.5448 9.9578 766 | -4.6684 -0.8566 15.0139 767 | -9.3601 -1.1116 16.6920 768 | -1.3919 -0.5293 6.4763 769 | 8.5950 -0.0459 8.0291 770 | 8.2840 -0.1185 10.9442 771 | -6.1936 -0.9509 15.1832 772 | -5.1669 -0.9501 17.5305 773 | 2.8996 -0.3514 6.5868 774 | -1.5690 -0.6344 9.3529 775 | 4.6527 -0.3665 12.2576 776 | -9.0422 -1.1715 16.6665 777 | -5.5902 -0.8259 6.3025 778 | -0.7036 -0.5780 7.0469 779 | -3.1628 -0.7410 9.7569 780 | -4.8314 -0.9548 15.0100 781 | -4.7237 -0.9696 17.1280 782 | 3.3198 -0.3923 6.2091 783 | 2.2020 -0.4674 7.0678 784 | -7.3534 -1.0396 10.8438 785 | -4.3695 -0.9559 15.1894 786 | -5.3373 -1.0641 17.5331 787 | -1.2121 -0.6405 6.4331 788 | 6.1392 -0.3231 8.4586 789 | 8.6863 -0.2278 10.4379 790 | -6.1863 -1.0981 15.1673 791 | -7.3976 -1.2072 17.5338 792 | -1.2856 -0.6878 6.2597 793 | 4.5847 -0.4325 8.0941 794 | 4.4960 -0.4446 10.9518 795 | -6.5009 -1.1614 15.7654 796 | 4.5436 -0.4250 5.7805 797 | 4.7667 -0.4241 6.9177 798 | -7.6107 -1.1413 9.9053 799 | -4.9853 -1.1035 15.0797 800 | -7.8059 -1.3029 17.7547 801 | 1.3441 -0.6435 6.7212 802 | -2.0589 -0.8484 9.0510 803 | 4.0929 -0.5999 11.0351 804 | -7.1301 -1.2557 16.0234 805 | 5.7030 -0.4369 5.9068 806 | -1.6900 -0.8649 8.0220 807 | -1.1700 -0.8640 9.3843 808 | -5.9719 -1.2255 15.0871 809 | -7.8399 -1.3733 17.6751 810 | -0.7118 -0.8068 6.4477 811 | 4.1972 -0.5989 8.0250 812 | -7.2149 -1.2136 10.5207 813 | -5.5697 -1.2440 15.5416 814 | -6.1254 -1.2858 17.6969 815 | 1.1672 -0.7652 6.9783 816 | -2.2431 -0.9705 8.6000 817 | 8.4218 -0.4527 10.4782 818 | -8.2199 -1.4333 16.1610 819 | 6.9624 -0.4693 5.7653 820 | 2.8948 -0.7037 6.9595 821 | -1.5080 -0.9382 8.6099 822 | 7.4712 -0.5344 10.3139 823 | -7.6693 -1.4435 15.8540 824 | -1.8767 -0.9752 5.9617 825 | 1.8307 -0.8005 6.9720 826 | 2.9155 -0.7818 8.9485 827 | 4.8283 -0.7363 11.7897 828 | -9.3327 -1.5744 16.7773 829 | -2.5506 -1.0541 6.4026 830 | 4.3818 -0.7210 7.9055 831 | 4.0656 -0.7398 9.3970 832 | 4.1522 -0.7650 11.3574 833 | -8.4915 -1.5562 16.3037 834 | 0.7650 -0.9036 6.2100 835 | -7.2600 -1.3424 7.9631 836 | 4.1797 -0.8025 9.4684 837 | 4.1054 -0.8146 11.0303 838 | -9.9912 -1.6782 16.7392 839 | -4.2994 -1.2161 6.5309 840 | -7.2209 -1.3747 8.0312 841 | 4.3982 -0.8220 9.6501 842 | -5.8495 -1.4569 15.2324 843 | -5.7102 -1.4828 17.2236 844 | -4.0144 -1.2402 6.6238 845 | -7.1672 -1.4378 8.3084 846 | 4.5062 -0.8617 9.7169 847 | -5.9849 -1.4773 15.3418 848 | -7.0087 -1.5833 18.0728 849 | 2.6758 -0.9295 6.8707 850 | 8.7778 -0.6385 8.3551 851 | 4.1579 -0.9351 10.8963 852 | -7.0691 -1.6203 17.2686 853 | -0.5392 -1.1266 6.5412 854 | 5.3404 -0.8470 8.0134 855 | 4.7072 -0.9346 9.8843 856 | -7.3264 -1.6288 15.8764 857 | 2.8646 -0.9761 6.1643 858 | 4.4942 -0.9035 7.1627 859 | -6.9599 -1.5502 9.2449 860 | 5.1603 -0.9556 10.3469 861 | -7.8163 -1.7261 17.8183 862 | -3.7777 -1.3752 7.0002 863 | 4.7534 -0.9437 8.3151 864 | 4.8315 -0.9653 9.8625 865 | -7.9126 -1.7701 16.1143 866 | 2.2085 -1.0548 6.3414 867 | -6.7173 -1.5807 8.0801 868 | -3.2429 -1.4285 9.3975 869 | 5.1938 -1.0101 10.3306 870 | -6.5190 -1.7613 17.7574 871 | 7.8617 -0.8280 6.6033 872 | 4.8161 -1.0108 7.8092 873 | 7.1307 -0.9221 9.4993 874 | -9.1771 -1.8958 15.6912 875 | -4.9474 -1.5335 6.5757 876 | -6.3459 -1.6267 7.6109 877 | -6.5071 -1.6596 8.9820 878 | 4.0862 -1.1405 10.6768 879 | -8.0716 -1.9224 18.2553 880 | -3.5525 -1.5068 7.1652 881 | 3.0867 -1.1777 8.1300 882 | -4.2646 -1.6007 10.0956 883 | -6.5194 -1.8579 17.5956 884 | 3.8434 -1.1252 6.5253 885 | 4.5780 -1.1558 7.9085 886 | 5.0004 -1.1438 9.5400 887 | -8.0743 -1.9505 16.0708 888 | -2.9809 -1.5370 6.6463 889 | 3.4947 -1.2203 7.8119 890 | -5.8162 -1.7132 9.6225 891 | -9.0619 -1.9999 15.8255 892 | -3.0133 -1.5742 6.6668 893 | -1.4346 -1.5021 7.8269 894 | 8.6741 -0.9895 8.8838 895 | -8.1692 -2.0097 15.2481 896 | 7.6078 -1.0150 6.3637 897 | 4.7495 -1.1996 7.6162 898 | -3.5148 -1.6904 9.5075 899 | -9.0726 -2.0986 15.5789 900 | 3.8556 -1.2874 6.8626 901 | -6.2405 -1.8496 8.5491 902 | 5.3029 -1.2853 10.6427 903 | 7.2928 -1.1304 6.1994 904 | -6.1223 -1.8797 8.6123 905 | 5.3372 -1.2908 9.9159 906 | -5.9518 -1.8720 6.8573 907 | 5.6443 -1.2868 8.0127 908 | 7.4087 -1.2104 9.4846 909 | 7.0836 -1.2098 6.1120 910 | 8.4422 -1.1699 7.7329 911 | 8.1770 -1.1900 9.4231 912 | 3.7242 -1.4195 6.0369 913 | -0.7608 -1.6604 7.8006 914 | -5.2600 -1.9581 9.5637 915 | -0.9257 -1.6971 5.9885 916 | 7.9170 -1.2492 6.8392 917 | -5.4530 -1.9502 8.5899 918 | -4.7761 -1.9730 9.8969 919 | 4.8225 -1.4048 6.3491 920 | -6.2362 -2.0488 7.9850 921 | -3.5352 -1.9299 9.3289 922 | -4.7618 -1.9721 6.1925 923 | -3.9193 -1.9490 7.2832 924 | 8.4525 -1.2924 8.0807 925 | 5.0984 -1.5468 10.9255 926 | 1.2936 -1.6993 6.6773 927 | -6.1680 -2.1056 7.9466 928 | -4.8543 -2.0440 9.5481 929 | -5.9043 -2.0750 6.4668 930 | -0.8647 -1.8418 7.5559 931 | 6.6709 -1.4896 8.5948 932 | -8.7427 -2.4257 15.2662 933 | -3.2956 -2.0153 6.9573 934 | 5.9007 -1.5518 7.9201 935 | 7.9665 -1.4316 9.0409 936 | -6.0005 -2.1768 6.5735 937 | -2.3261 -2.0124 7.6273 938 | -3.6878 -2.0994 8.7008 939 | -8.4869 -2.4828 15.4817 940 | 2.4059 -1.7852 6.8806 941 | 6.1537 -1.5883 8.0857 942 | -7.8890 -2.4798 14.9355 943 | 7.1823 -1.5606 6.4040 944 | 8.1561 -1.5328 7.5965 945 | -8.2936 -2.5383 15.0537 946 | 7.3220 -1.5905 6.5037 947 | -3.5866 -2.1990 8.4265 948 | -4.6805 -2.2369 6.1060 949 | 1.2914 -1.9483 6.8535 950 | -5.0488 -2.2879 8.6049 951 | 6.0642 -1.7049 6.3005 952 | -5.8008 -2.3770 8.0069 953 | 4.5840 -1.8795 10.9726 954 | 1.2872 -2.0177 6.8121 955 | -5.2273 -2.3827 8.3643 956 | 3.6467 -1.9143 6.0413 957 | -2.1611 -2.2444 7.3839 958 | 5.1586 -1.9237 10.6366 959 | -1.8754 -2.2579 7.0935 960 | 3.7847 -1.9871 8.3717 961 | 1.2930 -2.1192 6.6352 962 | 6.5797 -1.8536 7.8210 963 | -4.2401 -2.4390 6.3664 964 | 6.0712 -1.9151 7.2096 965 | 4.7639 -2.0535 10.8359 966 | -2.9538 -2.4206 7.0962 967 | -3.5043 -2.4738 8.3558 968 | -1.4344 -2.3472 6.5161 969 | 4.2664 -2.0537 7.5481 970 | 1.6721 -2.2273 6.2696 971 | 4.0524 -2.1606 9.3400 972 | -3.8773 -2.5848 8.5588 973 | 3.9315 -2.2131 7.7637 974 | -5.8185 -2.7353 7.9585 975 | -3.2342 -2.6585 7.7614 976 | -3.3619 -2.6896 8.0836 977 | 4.0908 -2.3509 8.1094 978 | -3.6621 -2.7719 8.4079 979 | 5.2571 -2.3545 9.3997 980 | -3.9709 -2.8807 6.3759 981 | 4.4315 -2.5182 8.5859 982 | -5.8963 -3.0553 6.2043 983 | -3.7099 -3.0045 7.6700 984 | -4.3111 -3.1125 8.3861 985 | -5.8349 -3.2494 7.7066 986 | -3.9438 -3.2184 7.6043 987 | -3.9904 -3.2392 6.2746 988 | -4.2980 -3.3279 7.4046 989 | -4.5121 -3.3979 8.2165 990 | -4.5508 -3.4683 8.0010 991 | -4.9866 -3.5443 6.4091 992 | -4.8463 -3.6613 8.1185 993 | -4.7784 -3.7229 7.0993 994 | -5.7749 -3.9079 7.4811 995 | -5.6000 -4.1520 7.8911 996 | -1.6056 0.9585 15.4081 997 | 4.0272 0.4909 6.4176 998 | -1.3233 -0.6706 6.2088 999 | 4.6087 -1.0100 8.3717 1000 | 4.9524 -1.5333 8.3707 1001 | -------------------------------------------------------------------------------- /examples/robust_pgo_mc.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | #include 13 | #include 14 | #include 15 | 16 | #include "pgo_utils.h" 17 | 18 | /** 19 | * graph - the uncorrupted factor graph 20 | * initial_values - the initial guess (usually odometry) 21 | * outlier_pct - fraction in [0,1] of outliers 22 | * random_seed - the random seed to use 23 | * is3D - true if the dataset is 3D 24 | * dataset_name - the name of the dataset 25 | */ 26 | void run_experiment3D(const gtsam::NonlinearFactorGraph& graph, 27 | const gtsam::Values& initial_values, double outlier_pct, 28 | size_t random_seed, std::string dataset_name) { 29 | /// 1. Build outlier graph. 30 | // Add prior on the pose having index (key) = 0 31 | gtsam::NonlinearFactorGraph graphWithOutliers = graph; 32 | 33 | gtsam::Vector6 prior_sigmas; 34 | prior_sigmas << 1e-8, 1e-8, 1e-8, 1e-6, 1e-6, 1e-6; 35 | gtsam::noiseModel::Diagonal::shared_ptr priorModel = 36 | gtsam::noiseModel::Diagonal::Sigmas(prior_sigmas); 37 | graphWithOutliers.add( 38 | gtsam::PriorFactor(0, gtsam::Pose3(), priorModel)); 39 | std::cout << "Adding prior on pose 0 " << std::endl; 40 | 41 | // Give a very coarse estimate for outlier sigmas. Derived from Olson and 42 | // Agarwal 2013 who recommend 10^7 for outlier variance, we conservatively 43 | // round up to 4000 for sigmas. 44 | gtsam::Vector6 outlier_sigmas; 45 | outlier_sigmas << 4000, 4000, 4000, 4000, 4000, 4000; 46 | gtsam::noiseModel::Diagonal::shared_ptr outlierModel = 47 | gtsam::noiseModel::Diagonal::Sigmas(outlier_sigmas); 48 | 49 | double outlier_prob = 0.5; 50 | std::vector lc_probabilities{(1.0 - outlier_prob), outlier_prob}; 51 | 52 | // We'll use this to save the inlier model so we can create the inlier 53 | // hypotheses. 54 | gtsam::SharedNoiseModel inlier_model; 55 | 56 | // Make a HybridFactorGraph to store the problem data. 57 | dcsam::HybridFactorGraph hfg; 58 | 59 | // Keep track of loop closure index. 60 | size_t k = 0; 61 | 62 | // Keep track of known inliers (odometry) for GNC. 63 | size_t known_inlier_idx = 0; 64 | gtsam::GncParams::IndexVector knownInliers; 65 | 66 | // Add all good measurements. 67 | for (const auto& factor : graphWithOutliers) { 68 | // Ensure that we correctly retrieve a BetweenFactor 69 | boost::shared_ptr> bwFactor = 70 | boost::dynamic_pointer_cast>(factor); 71 | if (bwFactor && isLoopClosure(*bwFactor)) { 72 | // If the meaasurement is a loop closure, we add inlier and outlier 73 | // hypotheses. 74 | auto keys = bwFactor->keys(); 75 | 76 | // We'll save the last inlier model to use for all our random 77 | // measuremenets. 78 | inlier_model = bwFactor->noiseModel(); 79 | // std::cout << inlier_model->sigmas() << std::endl; 80 | 81 | gtsam::Vector6 outlier_sigmas = 4000.0 * inlier_model->sigmas(); 82 | 83 | gtsam::noiseModel::Diagonal::shared_ptr outlierModel = 84 | gtsam::noiseModel::Diagonal::Sigmas(outlier_sigmas); 85 | 86 | // Build a vector of components factors (inlier model, outlier model) 87 | std::vector> components; 88 | components.push_back(*bwFactor); 89 | components.push_back(gtsam::BetweenFactor( 90 | keys[0], keys[1], bwFactor->measured(), outlierModel)); 91 | 92 | // Create a discrete key to index into components. Cardinality is 2 93 | // since a loop closure is either an inlier (0) or outlier (1). 94 | gtsam::DiscreteKey dk(gtsam::Symbol('d', k), 2); 95 | dcsam::DCMixtureFactor dcmf(bwFactor->keys(), dk, components, false); 96 | hfg.push_dc(dcmf); 97 | 98 | dcsam::DiscretePriorFactor dpf(dk, lc_probabilities); 99 | hfg.push_discrete(dpf); 100 | k++; 101 | 102 | } else { 103 | hfg.push_nonlinear(factor); 104 | // if (bwFactor) { 105 | knownInliers.push_back(known_inlier_idx); 106 | // } 107 | } 108 | // Skip the prior factor when counting odometry measurements 109 | // if (bwFactor) { 110 | known_inlier_idx++; 111 | // } 112 | } 113 | 114 | /// 2. For each method: solve graph. 115 | 116 | size_t num_original_lc = k; 117 | 118 | std::cout << "Processed " << num_original_lc << " loop closures." 119 | << std::endl; 120 | 121 | // We want num_outliers such that: 122 | // outlier_pct = num_outliers / (num_outliers + num_original) 123 | // 124 | // A little algebra reveals: 125 | // num_outliers = num_original_lc * (outlier_pct / (1 - outlier_pct)) 126 | // 127 | // Cast is kosher since we know outlier_pct >= 0 and num_original_lc is 128 | // of type size_t. 129 | size_t num_outliers = 130 | (size_t)((outlier_pct / (1.0 - outlier_pct)) * num_original_lc); 131 | 132 | gtsam::NonlinearFactorGraph outlierGraph = generateRandomLoopClosures( 133 | graph.keyVector(), num_outliers, inlier_model, true, random_seed); 134 | 135 | // Add all outlier measurements. 136 | for (const auto& factor : outlierGraph) { 137 | // Ensure that we correctly retrieve a BetweenFactor 138 | boost::shared_ptr> bwFactor = 139 | boost::dynamic_pointer_cast>(factor); 140 | if (bwFactor && isLoopClosure(*bwFactor)) { 141 | // If the meaasurement is a loop closure, we add inlier and outlier 142 | // hypotheses. 143 | auto keys = bwFactor->keys(); 144 | 145 | inlier_model = bwFactor->noiseModel(); 146 | 147 | gtsam::Vector6 outlier_sigmas = 4000.0 * inlier_model->sigmas(); 148 | 149 | gtsam::noiseModel::Diagonal::shared_ptr outlierModel = 150 | gtsam::noiseModel::Diagonal::Sigmas(outlier_sigmas); 151 | 152 | // Build a vector of components factors (inlier model, outlier model) 153 | std::vector> components; 154 | components.push_back(*bwFactor); 155 | components.push_back(gtsam::BetweenFactor( 156 | keys[0], keys[1], bwFactor->measured(), outlierModel)); 157 | 158 | // Create a discrete key to index into components. Cardinality is 2 159 | // since a loop closure is either an inlier (0) or outlier (1). 160 | gtsam::DiscreteKey dk(gtsam::Symbol('d', k), 2); 161 | dcsam::DCMixtureFactor dcmf(bwFactor->keys(), dk, components, false); 162 | hfg.push_dc(dcmf); 163 | 164 | // Set up the discrete weights for each factor. 165 | dcsam::DiscretePriorFactor dpf(dk, lc_probabilities); 166 | hfg.push_discrete(dpf); 167 | 168 | // Add outlier factor to graph so we can visualize later. 169 | graphWithOutliers.add(*bwFactor); 170 | k++; 171 | } else { 172 | hfg.push_nonlinear(factor); 173 | } 174 | } 175 | std::cout << "HFG size: " << hfg.size() << std::endl; 176 | 177 | // Currently DCSAM requires that we provide initial discrete values, but 178 | // they aren't actually used since we perform the discrete solve first, so 179 | // we just set them all to 0. 180 | dcsam::DiscreteValues initial_discrete; 181 | for (size_t i = 0; i < k; i++) { 182 | initial_discrete[gtsam::Symbol('d', i)] = 0; 183 | } 184 | 185 | // Create a solver instance and use it to optimize the graph. 186 | dcsam::DCSAM dcsam; 187 | 188 | using std::chrono::duration; 189 | using std::chrono::duration_cast; 190 | using std::chrono::milliseconds; 191 | 192 | std::vector dcsam_compute_times, dcsam_costs, dcsam_hybrid_costs; 193 | auto t1 = std::chrono::high_resolution_clock::now(); 194 | dcsam.update(hfg, initial_values, initial_discrete); 195 | auto t2 = std::chrono::high_resolution_clock::now(); 196 | // Get milliseconds as int 197 | auto ms_int = std::chrono::duration_cast(t2 - t1); 198 | // Convert to double 199 | double ms_double = static_cast(ms_int.count()); 200 | // Get compute time in sec 201 | dcsam_compute_times.push_back(ms_double / 1000.0); 202 | 203 | // Perform a few more iterations to converge. 204 | dcsam::DCValues result; 205 | std::vector dc_results; 206 | result = dcsam.calculateEstimate(); 207 | dc_results.push_back(result); 208 | dcsam_costs.push_back(graph.error(result.continuous)); 209 | dcsam_hybrid_costs.push_back(hybrid_error(hfg, result)); 210 | gtsam::writeG2o(graphWithOutliers, result.continuous, "out_robust0.g2o"); 211 | for (size_t iter = 0; iter < 49; iter++) { 212 | t1 = std::chrono::high_resolution_clock::now(); 213 | dcsam.update(); 214 | t2 = std::chrono::high_resolution_clock::now(); 215 | ms_int = std::chrono::duration_cast(t2 - t1); 216 | ms_double = static_cast(ms_int.count()); 217 | dcsam_compute_times.push_back(ms_double / 1000.0); 218 | 219 | result = dcsam.calculateEstimate(); 220 | dc_results.push_back(result); 221 | dcsam_costs.push_back(graph.error(result.continuous)); 222 | dcsam_hybrid_costs.push_back(hybrid_error(hfg, result)); 223 | 224 | std::string fname = "out_robust" + std::to_string(iter + 1) + ".g2o"; 225 | gtsam::writeG2o(graphWithOutliers, result.continuous, fname); 226 | // dcsam::DCMarginals marg = 227 | // dcsam.getMarginals(dcsam.getNonlinearFactorGraph(), 228 | // result.continuous, 229 | // dcsam.getDiscreteFactorGraph()); 230 | // std::string marg_fname = "marg_robust" + std::to_string(iter + 1) + 231 | // ".txt"; writeDiscreteMarginals(dcsam.getDiscreteFactorGraph().keys(), 232 | // marg.discrete, 233 | // marg_fname); 234 | 235 | if (dc_results[iter + 1].continuous.equals(dc_results[iter].continuous) && 236 | dc_results[iter + 1].discrete.equals(dc_results[iter].discrete)) { 237 | // We have reached convergence 238 | std::cout << "We have reached convergence!" << std::endl; 239 | break; 240 | } 241 | } 242 | 243 | // Perform a few more iterations 244 | // for (size_t j = 0; j < 10; j++) { 245 | // t1 = std::chrono::high_resolution_clock::now(); 246 | // dcsam.update(); 247 | // t2 = std::chrono::high_resolution_clock::now(); 248 | // ms_int = std::chrono::duration_cast(t2 - t1); 249 | // ms_double = static_cast(ms_int.count()); 250 | // dcsam_compute_times.push_back(ms_double / 1000.0); 251 | // result = dcsam.calculateEstimate(); 252 | // dcsam_costs.push_back(graph.error(result.continuous)); 253 | // dcsam_hybrid_costs.push_back(hybrid_error(hfg, result)); 254 | // } 255 | // auto t2 = std::chrono::high_resolution_clock::now(); 256 | 257 | // Get milliseconds as int 258 | // auto ms_int = std::chrono::duration_cast(t2 - 259 | // t1); 260 | 261 | // Convert to double 262 | // double ms_double = static_cast(ms_int.count()); 263 | 264 | // Total time in seconds: 265 | // double total_time = ms_double / 1000.0; 266 | 267 | // std::cout << "Total time [DCSAM]: " << total_time << " seconds." << 268 | // std::endl; std::cout << "Avg. time/iter [DCSAM]: " << total_time / 7.0 << " 269 | // seconds." 270 | // << std::endl; 271 | assert(dcsam_costs.size() == dcsam_compute_times.size()); 272 | assert(dcsam_costs.size() == dcsam_hybrid_costs.size()); 273 | double total_time_dcsam = 0.0; 274 | for (size_t idx = 0; idx < dcsam_costs.size(); idx++) { 275 | total_time_dcsam += dcsam_compute_times[idx]; 276 | std::cout << "idx, time, cost, dcCost" << std::endl; 277 | std::cout << idx << ", " << dcsam_compute_times[idx] << ", " 278 | << dcsam_costs[idx] << ", " << dcsam_hybrid_costs[idx] 279 | << std::endl; 280 | std::cout << "total time: " << total_time_dcsam << std::endl; 281 | } 282 | 283 | double total_time_lm, total_time_gnc; 284 | 285 | result = dcsam.calculateEstimate(); 286 | std::cout << "Initial cost: " << graph.error(initial_values) << std::endl; 287 | std::cout << "Final cost [DCSAM]: " << graph.error(result.continuous) 288 | << std::endl; 289 | 290 | // Make sure we add the prior factor to the outlier graph before passing to LM 291 | // and GNC. This addresses gauge ambiguity. 292 | gtsam::NonlinearFactorGraph graphWithOutliersAndPrior = 293 | graphWithOutliers.clone(); 294 | 295 | // graphWithOutliersAndPrior.add( 296 | // gtsam::PriorFactor(0, gtsam::Pose3(), priorModel)); 297 | 298 | // Solve the non-robust version of the graph 299 | gtsam::LevenbergMarquardtOptimizer lm(graphWithOutliersAndPrior, 300 | initial_values); 301 | 302 | t1 = std::chrono::high_resolution_clock::now(); 303 | gtsam::Values lm_result = lm.optimize(); 304 | t2 = std::chrono::high_resolution_clock::now(); 305 | 306 | std::cout << "Final cost [LM]: " << graph.error(lm_result) << std::endl; 307 | 308 | // Get milliseconds as int 309 | ms_int = std::chrono::duration_cast(t2 - t1); 310 | 311 | // Convert to double 312 | ms_double = static_cast(ms_int.count()); 313 | total_time_lm = ms_double / 1000.0; 314 | 315 | std::cout << "Total time [LM]: " << total_time_lm << " seconds." << std::endl; 316 | 317 | /// Solve with GNC 318 | gtsam::GncParams gncParams; 319 | 320 | // Let GNC know that odometry measurements are inliers: 321 | std::cout << "Known inliers size: " << knownInliers.size() << std::endl; 322 | gncParams.knownInliers = knownInliers; 323 | gncParams.lossType = gtsam::GncLossType::TLS; 324 | // Collect summary stats from GNC 325 | // gncParams.verbosity = 326 | // gtsam::GncParams::Verbosity::SUMMARY; 327 | gncParams.maxIterations = 50; 328 | 329 | // Make the optimizer and solve. 330 | auto gnc = 331 | gtsam::GncOptimizer>( 332 | graphWithOutliersAndPrior, initial_values, gncParams); 333 | 334 | std::cout << "Default inlier cost threshold = " 335 | << gnc.getInlierCostThresholds()[0] << std::endl; 336 | 337 | // We found that setting the inlier cost threshold to 0.5 gave us the best 338 | // results on the `parking-garage.g2o` dataset, and setting the to 4 gave the 339 | // best results on `sphere2500.g2o` 340 | // gnc.setInlierCostThresholds(4.0); 341 | gnc.setInlierCostThresholds(0.5); 342 | 343 | t1 = std::chrono::high_resolution_clock::now(); 344 | gtsam::Values gnc_result = gnc.optimize(); 345 | t2 = std::chrono::high_resolution_clock::now(); 346 | 347 | std::cout << "Final cost [GNC]: " << graph.error(gnc_result) << std::endl; 348 | 349 | // Get milliseconds as int 350 | ms_int = std::chrono::duration_cast(t2 - t1); 351 | 352 | // Convert to double 353 | ms_double = static_cast(ms_int.count()); 354 | total_time_gnc = ms_double / 1000.0; 355 | 356 | std::cout << "Total time [GNC]: " << total_time_gnc << " seconds." 357 | << std::endl; 358 | 359 | std::cout << "OUTLIER PCT" << std::to_string((int)(100 * outlier_pct)) 360 | << std::endl; 361 | std::string path_prefix = "../../output/robust_pgo_vanilla/" + dataset_name + 362 | "/" + std::to_string((int)(100 * outlier_pct)) + 363 | "/" + std::to_string(random_seed) + "/"; 364 | 365 | std::cout << "path_prefix: " << path_prefix << std::endl; 366 | 367 | // use "writeG2o" to save file. 368 | gtsam::writeG2o(graphWithOutliers, lm_result, 369 | path_prefix + "out_nonrobust.g2o"); 370 | gtsam::writeG2o(graphWithOutliers, result.continuous, 371 | path_prefix + "out_robust.g2o"); 372 | gtsam::writeG2o(graphWithOutliers, gnc_result, path_prefix + "out_gnc.g2o"); 373 | 374 | // All loop closures _after_ this number should be visualized as outliers. 375 | std::ofstream file(path_prefix + "orig_graph_size_out.txt"); 376 | file << graph.size(); 377 | 378 | // Write timing info 379 | std::ofstream time_file(path_prefix + "times.txt"); 380 | time_file << "DCSAM: " << std::to_string(total_time_dcsam) << "\n" 381 | << "GNC: " << std::to_string(total_time_gnc) << "\n" 382 | << "LM: " << total_time_lm << "\n"; 383 | 384 | /// 3. Collect stats, final trajectory, and output to file. 385 | return; 386 | } 387 | 388 | /** 389 | * graph - the uncorrupted factor graph 390 | * initial_values - the initial guess (usually odometry) 391 | * outlier_pct - fraction in [0,1] of outliers 392 | * random_seed - the random seed to use 393 | * dataset_name - the name of the dataset 394 | */ 395 | void run_experiment2D(const gtsam::NonlinearFactorGraph& graph, 396 | const gtsam::Values& initial_values, double outlier_pct, 397 | size_t random_seed, std::string dataset_name) { 398 | /// 1. Build outlier graph. 399 | // Add prior on the pose having index (key) = 0 400 | gtsam::NonlinearFactorGraph graphWithOutliers = graph; 401 | 402 | gtsam::Vector3 prior_sigmas; 403 | prior_sigmas << 1e-6, 1e-6, 1e-8; 404 | gtsam::noiseModel::Diagonal::shared_ptr priorModel = 405 | gtsam::noiseModel::Diagonal::Sigmas(prior_sigmas); 406 | graphWithOutliers.add( 407 | gtsam::PriorFactor(0, gtsam::Pose2(), priorModel)); 408 | std::cout << "Adding prior on pose 0 " << std::endl; 409 | 410 | // Give a very coarse estimate for outlier sigmas. Derived from Olson and 411 | // Agarwal 2013 who recommend 10^7 for outlier variance, we conservatively 412 | // round up to 4000 for sigmas. 413 | gtsam::Vector3 outlier_sigmas; 414 | outlier_sigmas << 4000, 4000, 4000; 415 | gtsam::noiseModel::Diagonal::shared_ptr outlierModel = 416 | gtsam::noiseModel::Diagonal::Sigmas(outlier_sigmas); 417 | 418 | double outlier_prob = 0.5; 419 | std::vector lc_probabilities{(1.0 - outlier_prob), outlier_prob}; 420 | 421 | // double outlier_prob = 0.5; 422 | // std::vector lc_probabilities{(1.0 - outlier_prob), outlier_prob}; 423 | 424 | // We'll use this to save the inlier model so we can create the inlier 425 | // hypotheses. 426 | gtsam::SharedNoiseModel inlier_model; 427 | 428 | // Make a HybridFactorGraph to store the problem data. 429 | dcsam::HybridFactorGraph hfg; 430 | 431 | // Keep track of loop closure index. 432 | size_t k = 0; 433 | 434 | // Keep track of known inliers (odometry) for GNC. 435 | size_t known_inlier_idx = 0; 436 | gtsam::GncParams::IndexVector knownInliers; 437 | 438 | // Add all good measurements. 439 | for (const auto& factor : graphWithOutliers) { 440 | // Ensure that we correctly retrieve a BetweenFactor 441 | boost::shared_ptr> bwFactor = 442 | boost::dynamic_pointer_cast>(factor); 443 | if (bwFactor && isLoopClosure(*bwFactor)) { 444 | // If the meaasurement is a loop closure, we add inlier and outlier 445 | // hypotheses. 446 | auto keys = bwFactor->keys(); 447 | 448 | // We'll save the last inlier model to use for all our random 449 | // measuremenets. 450 | inlier_model = bwFactor->noiseModel(); 451 | // std::cout << inlier_model->sigmas() << std::endl; 452 | 453 | // Build a vector of components factors (inlier model, outlier model) 454 | std::vector> components; 455 | components.push_back(*bwFactor); 456 | 457 | gtsam::Vector3 outlier_sigmas = 4000.0 * inlier_model->sigmas(); 458 | 459 | gtsam::noiseModel::Diagonal::shared_ptr outlierModel = 460 | gtsam::noiseModel::Diagonal::Sigmas(outlier_sigmas); 461 | 462 | components.push_back(gtsam::BetweenFactor( 463 | keys[0], keys[1], bwFactor->measured(), outlierModel)); 464 | 465 | // Create a discrete key to index into components. Cardinality is 2 466 | // since a loop closure is either an inlier (0) or outlier (1). 467 | gtsam::DiscreteKey dk(gtsam::Symbol('d', k), 2); 468 | dcsam::DCMixtureFactor dcmf(bwFactor->keys(), dk, components, false); 469 | hfg.push_dc(dcmf); 470 | 471 | dcsam::DiscretePriorFactor dpf(dk, lc_probabilities); 472 | hfg.push_discrete(dpf); 473 | k++; 474 | 475 | } else { 476 | hfg.push_nonlinear(factor); 477 | // if (bwFactor) { 478 | knownInliers.push_back(known_inlier_idx); 479 | // } 480 | } 481 | // Skip the prior factor when counting odometry measurements 482 | // if (bwFactor) { 483 | known_inlier_idx++; 484 | // } 485 | } 486 | 487 | /// 2. For each method: solve graph. 488 | 489 | size_t num_original_lc = k; 490 | 491 | std::cout << "Processed " << num_original_lc << " loop closures." 492 | << std::endl; 493 | 494 | // We want num_outliers such that: 495 | // outlier_pct = num_outliers / (num_outliers + num_original) 496 | // 497 | // A little algebra reveals: 498 | // num_outliers = num_original_lc * (outlier_pct / (1 - outlier_pct)) 499 | // 500 | // Cast is kosher since we know outlier_pct >= 0 and num_original_lc is 501 | // of type size_t. 502 | size_t num_outliers = 503 | (size_t)((outlier_pct / (1.0 - outlier_pct)) * num_original_lc); 504 | 505 | gtsam::NonlinearFactorGraph outlierGraph = generateRandomLoopClosures( 506 | graph.keyVector(), num_outliers, inlier_model, false, random_seed); 507 | 508 | // Add all outlier measurements. 509 | for (const auto& factor : outlierGraph) { 510 | // Ensure that we correctly retrieve a BetweenFactor 511 | boost::shared_ptr> bwFactor = 512 | boost::dynamic_pointer_cast>(factor); 513 | if (bwFactor && isLoopClosure(*bwFactor)) { 514 | // If the meaasurement is a loop closure, we add inlier and outlier 515 | // hypotheses. 516 | auto keys = bwFactor->keys(); 517 | 518 | inlier_model = bwFactor->noiseModel(); 519 | 520 | // Build a vector of components factors (inlier model, outlier model) 521 | std::vector> components; 522 | components.push_back(*bwFactor); 523 | 524 | gtsam::Vector3 outlier_sigmas = 4000.0 * inlier_model->sigmas(); 525 | 526 | gtsam::noiseModel::Diagonal::shared_ptr outlierModel = 527 | gtsam::noiseModel::Diagonal::Sigmas(outlier_sigmas); 528 | components.push_back(gtsam::BetweenFactor( 529 | keys[0], keys[1], bwFactor->measured(), outlierModel)); 530 | 531 | // Create a discrete key to index into components. Cardinality is 2 532 | // since a loop closure is either an inlier (0) or outlier (1). 533 | gtsam::DiscreteKey dk(gtsam::Symbol('d', k), 2); 534 | dcsam::DCMixtureFactor dcmf(bwFactor->keys(), dk, components, false); 535 | hfg.push_dc(dcmf); 536 | 537 | // Set up the discrete weights for each factor. 538 | dcsam::DiscretePriorFactor dpf(dk, lc_probabilities); 539 | hfg.push_discrete(dpf); 540 | 541 | // Add outlier factor to graph so we can visualize later. 542 | graphWithOutliers.add(*bwFactor); 543 | k++; 544 | } else { 545 | hfg.push_nonlinear(factor); 546 | } 547 | } 548 | std::cout << "HFG size: " << hfg.size() << std::endl; 549 | 550 | // Currently DCSAM requires that we provide initial discrete values, but 551 | // they aren't actually used since we perform the discrete solve first, so 552 | // we just set them all to 0. 553 | dcsam::DiscreteValues initial_discrete; 554 | for (size_t i = 0; i < k; i++) { 555 | initial_discrete[gtsam::Symbol('d', i)] = 0; 556 | } 557 | 558 | // Create a solver instance and use it to optimize the graph. 559 | dcsam::DCSAM dcsam; 560 | 561 | using std::chrono::duration; 562 | using std::chrono::duration_cast; 563 | using std::chrono::milliseconds; 564 | 565 | std::vector dcsam_compute_times, dcsam_costs, dcsam_hybrid_costs; 566 | auto t1 = std::chrono::high_resolution_clock::now(); 567 | dcsam.update(hfg, initial_values, initial_discrete); 568 | auto t2 = std::chrono::high_resolution_clock::now(); 569 | // Get milliseconds as int 570 | auto ms_int = std::chrono::duration_cast(t2 - t1); 571 | // Convert to double 572 | double ms_double = static_cast(ms_int.count()); 573 | // Get compute time in sec 574 | dcsam_compute_times.push_back(ms_double / 1000.0); 575 | 576 | // Perform a few more iterations to converge. 577 | dcsam::DCValues result; 578 | std::vector dc_results; 579 | result = dcsam.calculateEstimate(); 580 | dc_results.push_back(result); 581 | dcsam_costs.push_back(graph.error(result.continuous)); 582 | dcsam_hybrid_costs.push_back(hybrid_error(hfg, result)); 583 | gtsam::writeG2o(graphWithOutliers, result.continuous, "out_robust0.g2o"); 584 | for (size_t iter = 0; iter < 49; iter++) { 585 | t1 = std::chrono::high_resolution_clock::now(); 586 | dcsam.update(); 587 | t2 = std::chrono::high_resolution_clock::now(); 588 | ms_int = std::chrono::duration_cast(t2 - t1); 589 | ms_double = static_cast(ms_int.count()); 590 | dcsam_compute_times.push_back(ms_double / 1000.0); 591 | 592 | result = dcsam.calculateEstimate(); 593 | dc_results.push_back(result); 594 | dcsam_costs.push_back(graph.error(result.continuous)); 595 | dcsam_hybrid_costs.push_back(hybrid_error(hfg, result)); 596 | 597 | std::string fname = "out_robust" + std::to_string(iter + 1) + ".g2o"; 598 | gtsam::writeG2o(graphWithOutliers, result.continuous, fname); 599 | 600 | if (dc_results[iter + 1].continuous.equals(dc_results[iter].continuous) && 601 | dc_results[iter + 1].discrete.equals(dc_results[iter].discrete)) { 602 | // We have reached convergence 603 | std::cout << "We have reached convergence!" << std::endl; 604 | break; 605 | } 606 | // dcsam::DCMarginals marg = 607 | // dcsam.getMarginals(dcsam.getNonlinearFactorGraph(), 608 | // result.continuous, 609 | // dcsam.getDiscreteFactorGraph()); 610 | // std::string marg_fname = "marg_robust" + std::to_string(iter + 1) + 611 | // ".txt"; writeDiscreteMarginals(dcsam.getDiscreteFactorGraph().keys(), 612 | // marg.discrete, 613 | // marg_fname); 614 | } 615 | 616 | // Perform a few more iterations 617 | // for (size_t j = 0; j < 100; j++) { 618 | // t1 = std::chrono::high_resolution_clock::now(); 619 | // dcsam.update(); 620 | // t2 = std::chrono::high_resolution_clock::now(); 621 | // ms_int = std::chrono::duration_cast(t2 - t1); 622 | // ms_double = static_cast(ms_int.count()); 623 | // dcsam_compute_times.push_back(ms_double / 1000.0); 624 | // result = dcsam.calculateEstimate(); 625 | // dc_results.push_back(result); 626 | // dcsam_costs.push_back(graph.error(result.continuous)); 627 | // dcsam_hybrid_costs.push_back(hybrid_error(hfg, result)); 628 | // } 629 | // auto t2 = std::chrono::high_resolution_clock::now(); 630 | 631 | // Get milliseconds as int 632 | // auto ms_int = std::chrono::duration_cast(t2 - 633 | // t1); 634 | 635 | // Convert to double 636 | // double ms_double = static_cast(ms_int.count()); 637 | 638 | // Total time in seconds: 639 | // double total_time = ms_double / 1000.0; 640 | 641 | // std::cout << "Total time [DCSAM]: " << total_time << " seconds." << 642 | // std::endl; std::cout << "Avg. time/iter [DCSAM]: " << total_time / 7.0 << " 643 | // seconds." 644 | // << std::endl; 645 | assert(dcsam_costs.size() == dcsam_compute_times.size()); 646 | assert(dcsam_costs.size() == dcsam_hybrid_costs.size()); 647 | double total_time_dcsam = 0.0; 648 | for (size_t idx = 0; idx < dcsam_costs.size(); idx++) { 649 | total_time_dcsam += dcsam_compute_times[idx]; 650 | std::cout << "idx, time, cost, dcCost" << std::endl; 651 | std::cout << idx << ", " << dcsam_compute_times[idx] << ", " 652 | << dcsam_costs[idx] << ", " << dcsam_hybrid_costs[idx] 653 | << std::endl; 654 | std::cout << "total time: " << total_time_dcsam << std::endl; 655 | if (idx > 0) { 656 | std::cout << "stationary?: " 657 | << (dc_results[idx].continuous.equals( 658 | dc_results[idx - 1].continuous) && 659 | dc_results[idx].discrete.equals( 660 | dc_results[idx - 1].discrete)) 661 | << std::endl; 662 | } 663 | } 664 | 665 | double total_time_lm, total_time_gnc; 666 | 667 | result = dcsam.calculateEstimate(); 668 | std::cout << "Initial cost: " << graph.error(initial_values) << std::endl; 669 | std::cout << "Final cost [DCSAM]: " << graph.error(result.continuous) 670 | << std::endl; 671 | 672 | // Make sure we add the prior factor to the outlier graph before passing to LM 673 | // and GNC. This addresses gauge ambiguity. 674 | gtsam::NonlinearFactorGraph graphWithOutliersAndPrior = 675 | graphWithOutliers.clone(); 676 | 677 | // graphWithOutliersAndPrior.add( 678 | // gtsam::PriorFactor(0, gtsam::Pose2(), priorModel)); 679 | 680 | // Solve the non-robust version of the graph 681 | gtsam::LevenbergMarquardtOptimizer lm(graphWithOutliersAndPrior, 682 | initial_values); 683 | 684 | t1 = std::chrono::high_resolution_clock::now(); 685 | gtsam::Values lm_result = lm.optimize(); 686 | t2 = std::chrono::high_resolution_clock::now(); 687 | 688 | std::cout << "Final cost [LM]: " << graph.error(lm_result) << std::endl; 689 | 690 | // Get milliseconds as int 691 | ms_int = std::chrono::duration_cast(t2 - t1); 692 | 693 | // Convert to double 694 | ms_double = static_cast(ms_int.count()); 695 | total_time_lm = ms_double / 1000.0; 696 | 697 | std::cout << "Total time [LM]: " << total_time_lm << " seconds." << std::endl; 698 | 699 | /// Solve with GNC 700 | gtsam::GncParams gncParams; 701 | 702 | // Let GNC know that odometry measurements are inliers: 703 | std::cout << "Known inliers size: " << knownInliers.size() << std::endl; 704 | gncParams.knownInliers = knownInliers; 705 | gncParams.lossType = gtsam::GncLossType::TLS; 706 | // Collect summary stats from GNC 707 | // gncParams.verbosity = 708 | // gtsam::GncParams::Verbosity::SUMMARY; 709 | gncParams.maxIterations = 50; 710 | 711 | // Make the optimizer and solve. 712 | auto gnc = 713 | gtsam::GncOptimizer>( 714 | graphWithOutliersAndPrior, initial_values, gncParams); 715 | 716 | std::cout << "Default inlier cost threshold = " 717 | << gnc.getInlierCostThresholds()[0] << std::endl; 718 | 719 | // We found that setting the inlier cost threshold to 0.5 gave us the best 720 | // results on the `parking-garage.g2o` dataset, and setting the to 4 gave the 721 | // best results on `sphere2500.g2o` 722 | // gnc.setInlierCostThresholds(4.0); 723 | 724 | t1 = std::chrono::high_resolution_clock::now(); 725 | gtsam::Values gnc_result = gnc.optimize(); 726 | t2 = std::chrono::high_resolution_clock::now(); 727 | 728 | std::cout << "Final cost [GNC]: " << graph.error(gnc_result) << std::endl; 729 | 730 | // Get milliseconds as int 731 | ms_int = std::chrono::duration_cast(t2 - t1); 732 | 733 | // Convert to double 734 | ms_double = static_cast(ms_int.count()); 735 | total_time_gnc = ms_double / 1000.0; 736 | 737 | std::cout << "Total time [GNC]: " << total_time_gnc << " seconds." 738 | << std::endl; 739 | 740 | std::cout << "OUTLIER PCT" << std::to_string((int)(100 * outlier_pct)) 741 | << std::endl; 742 | std::string path_prefix = "../../output/robust_pgo_vanilla/" + dataset_name + 743 | "/" + std::to_string((int)(100 * outlier_pct)) + 744 | "/" + std::to_string(random_seed) + "/"; 745 | 746 | std::cout << "path_prefix: " << path_prefix << std::endl; 747 | 748 | // use "writeG2o" to save file. 749 | gtsam::writeG2o(graphWithOutliers, lm_result, 750 | path_prefix + "out_nonrobust.g2o"); 751 | gtsam::writeG2o(graphWithOutliers, result.continuous, 752 | path_prefix + "out_robust.g2o"); 753 | gtsam::writeG2o(graphWithOutliers, gnc_result, path_prefix + "out_gnc.g2o"); 754 | 755 | // All loop closures _after_ this number should be visualized as outliers. 756 | std::ofstream file(path_prefix + "orig_graph_size_out.txt"); 757 | file << graph.size(); 758 | 759 | // Write timing info 760 | std::ofstream time_file(path_prefix + "times.txt"); 761 | time_file << "DCSAM: " << std::to_string(total_time_dcsam) << "\n" 762 | << "GNC: " << std::to_string(total_time_gnc) << "\n" 763 | << "LM: " << total_time_lm << "\n"; 764 | 765 | /// 3. Collect stats, final trajectory, and output to file. 766 | return; 767 | } 768 | 769 | int main(int argc, char** argv) { 770 | if (argc < 2) { 771 | std::cout << "Usage: " << argv[0] << " [.g2o file]" 772 | << " [outlier rate (int >= 0; default 0)]" 773 | << " [is3D (0/1; default 1)]" 774 | << " [num trials (default 1)]" << std::endl; 775 | exit(1); 776 | } 777 | 778 | // Defaults 779 | double outlier_pct = 0.0; 780 | bool is3D = true; 781 | size_t num_trials = 1; 782 | 783 | // Begin parsing input 784 | std::string path = argv[1]; 785 | 786 | std::string base_filename = path.substr(path.find_last_of("/\\") + 1); 787 | std::string::size_type const p(base_filename.find_last_of('.')); 788 | std::string file_without_extension = base_filename.substr(0, p); 789 | 790 | if (argc >= 3) { 791 | std::cout << "outlier percent " << atoi(argv[2]) << std::endl; 792 | outlier_pct = (double)(atoi(argv[2])) / 100.0; 793 | std::cout << "outlier percent " << outlier_pct << std::endl; 794 | } 795 | if ((argc >= 4) && (atoi(argv[3]) != 1)) { 796 | is3D = false; 797 | } 798 | if ((argc >= 5)) { 799 | assert(atoi(argv[4]) > 0); 800 | num_trials = atoi(argv[4]); 801 | } 802 | 803 | std::cout << "Running robust PGO experiment\n" 804 | << "=============================\n" 805 | << "dataset:\t" << file_without_extension << "\n" 806 | << "outlier_pct:\t" << outlier_pct << "\n" 807 | << "is3D?:\t\t" << is3D << "\n" 808 | << "num_trials:\t" << num_trials << "\n" 809 | << std::endl; 810 | 811 | gtsam::NonlinearFactorGraph::shared_ptr graph; 812 | gtsam::Values::shared_ptr initial; 813 | 814 | boost::tie(graph, initial) = gtsam::readG2o(path, is3D); 815 | 816 | std::cout << "Loaded a graph of size: " << graph->size() << std::endl; 817 | 818 | for (size_t i = 1; i < num_trials + 1; i++) { 819 | if (is3D) { 820 | run_experiment3D(*graph, *initial, outlier_pct, i, 821 | file_without_extension); 822 | } else { 823 | run_experiment2D(*graph, *initial, outlier_pct, i, 824 | file_without_extension); 825 | } 826 | } 827 | } 828 | -------------------------------------------------------------------------------- /data/pointclouds/bunny_sparse10_part1.xyz: -------------------------------------------------------------------------------- 1 | -2.2200 -3.8800 11.2600 2 | -8.8300 -3.0000 14.0600 3 | -4.3100 -2.9000 12.3400 4 | -3.1500 -0.9300 12.6300 5 | 3.4300 -2.4300 11.4700 6 | -6.8000 -2.6100 6.3100 7 | 1.0000 -3.1700 12.5100 8 | -2.9900 -0.5500 12.5300 9 | -7.2100 -5.3700 14.1400 10 | 0.6500 -4.5800 3.8600 11 | -6.6600 -5.9500 12.1800 12 | -6.2700 -3.7500 15.3900 13 | 4.0500 -1.9700 10.6900 14 | -8.7800 -1.9200 9.2900 15 | -6.9500 -4.8700 14.7000 16 | -3.7300 -0.4100 17.1200 17 | -8.9500 -1.3100 12.6800 18 | 0.5300 -1.0900 13.1800 19 | 1.3000 -2.1300 12.9700 20 | -1.3400 -0.8600 12.8900 21 | -4.3500 -4.8400 4.1200 22 | 0.0400 -2.9200 12.7700 23 | 4.1700 -2.3600 10.1300 24 | -0.6700 -1.3200 13.0500 25 | 0.5500 -4.6100 4.1400 26 | -4.5600 -1.1800 15.9300 27 | -7.0600 -5.9500 12.3200 28 | -2.2600 -1.1700 12.6600 29 | -5.0300 -5.0400 4.2700 30 | -3.8600 -4.6300 4.2400 31 | -2.0800 -5.5200 4.3500 32 | -1.0000 -5.2100 4.3300 33 | -0.0400 -4.8100 4.2900 34 | 0.9500 -4.4900 4.2700 35 | -1.0000 -4.0800 11.4100 36 | -0.2800 -4.1900 11.2800 37 | 0.1700 -3.2300 12.5400 38 | -5.2400 -4.9600 4.4000 39 | -4.2600 -4.7000 4.3800 40 | -2.2500 -0.6100 12.6200 41 | -2.1900 -5.3300 4.4700 42 | -1.2000 -5.2600 4.4700 43 | -0.2300 -4.8300 4.4400 44 | 0.7500 -4.5400 4.4200 45 | -0.6900 -4.1300 11.4200 46 | -7.5600 -5.9000 13.1600 47 | -6.8900 -5.6300 13.5800 48 | -1.1600 -2.7400 12.6600 49 | -4.5600 -4.6800 4.5200 50 | -3.5800 -4.4400 4.5100 51 | -2.3000 -5.2600 4.6000 52 | -1.3000 -5.2400 4.6000 53 | -0.3300 -4.7900 4.5700 54 | 0.6700 -4.7700 4.5900 55 | -3.1500 -3.5800 11.5200 56 | 4.2800 -1.8500 10.1400 57 | -3.1900 -0.4900 12.5600 58 | -4.2600 -2.3500 12.8200 59 | -4.9600 -4.6500 4.6600 60 | -3.9800 -4.4400 4.6500 61 | -2.3000 -5.1700 4.7300 62 | -1.3100 -5.1200 4.7300 63 | -0.3300 -4.8300 4.7100 64 | 0.6800 -4.9500 4.7400 65 | -7.2800 -5.6500 13.7200 66 | -6.6700 -4.6700 14.8400 67 | 3.7000 -2.7100 4.5400 68 | 4.1400 -2.1700 10.4200 69 | -5.1800 -4.4600 4.7800 70 | -4.1900 -4.3500 4.7800 71 | -3.1900 -4.2600 4.7800 72 | -1.4200 -4.9700 4.8600 73 | -0.4100 -5.0600 4.8900 74 | 0.6000 -5.1000 4.9000 75 | -6.7600 -5.9600 12.3200 76 | -6.9400 -5.0000 14.5600 77 | -0.0100 -1.6400 13.1300 78 | -8.6200 -3.9800 14.2000 79 | -3.5200 -0.8300 12.7600 80 | -4.4000 -4.2500 4.9100 81 | -3.3900 -4.2500 4.9200 82 | -2.2400 -4.8300 4.9900 83 | -1.2300 -4.8600 5.0000 84 | -0.2000 -5.1700 5.0400 85 | 0.8100 -5.2000 5.0500 86 | -0.8300 -1.4200 13.0300 87 | -2.8900 -0.5800 12.5100 88 | 4.3200 -2.8600 4.8500 89 | -8.7400 -0.7900 11.9900 90 | -3.6400 -2.5300 12.5400 91 | -3.8900 -4.3000 5.0600 92 | -2.9000 -4.1100 5.0700 93 | -1.8500 -4.5900 5.1000 94 | -0.8000 -5.1700 5.1700 95 | 0.2200 -5.3900 5.2000 96 | 1.2000 -5.1100 5.1800 97 | -7.1600 -5.9700 12.8900 98 | -0.2100 -2.7100 12.8700 99 | 4.2200 -2.8700 4.9900 100 | 2.4400 -2.5800 12.2900 101 | -4.6100 -3.9800 5.1600 102 | -3.5900 -4.2600 5.2000 103 | -3.2700 -3.2100 12.0600 104 | -1.3100 -5.0500 5.3000 105 | -0.2900 -5.3100 5.3300 106 | 0.7200 -5.3100 5.3400 107 | -6.9700 -5.8400 13.1700 108 | -7.4700 -5.7900 13.4500 109 | 4.0100 -2.8400 5.1300 110 | -6.2000 -4.3500 14.9700 111 | 1.5500 -2.7500 12.6700 112 | -4.4100 -4.0900 5.3200 113 | -3.3900 -4.2200 5.3400 114 | -6.5100 -3.2600 15.5700 115 | -1.1000 -5.1900 5.4500 116 | -0.0800 -5.4100 5.4800 117 | 0.9100 -5.2800 5.4800 118 | -7.2600 -5.9400 12.6000 119 | 3.8600 0.2200 10.6900 120 | 4.4200 -2.8700 5.2800 121 | -5.8100 -4.1600 14.9800 122 | -6.1400 -1.5200 15.5700 123 | -3.7900 -4.3200 5.4900 124 | -2.8100 -3.9600 5.4600 125 | -0.1300 -0.7700 13.1100 126 | -0.4800 -5.3600 5.6100 127 | 0.5300 -5.4400 5.6300 128 | 1.5000 -5.1600 5.6100 129 | 4.5900 -0.6200 9.3200 130 | -2.8400 -0.8800 12.5400 131 | 4.6200 -2.8600 5.4200 132 | -1.6700 -1.0500 12.8200 133 | -4.0900 -4.2700 5.6200 134 | -3.1000 -4.1200 5.6100 135 | -7.9500 -3.0500 15.4200 136 | -0.8900 -5.2700 5.7400 137 | 0.2200 -5.4000 5.7600 138 | 1.2100 -5.2200 5.7500 139 | -3.2400 -3.6900 11.3800 140 | -1.4500 -3.4600 12.0900 141 | 4.5100 -2.8300 5.5600 142 | 2.0700 -2.0600 12.6300 143 | -5.7000 -3.9100 15.2200 144 | -3.5800 -4.3500 5.7700 145 | -2.6200 -3.9200 5.7400 146 | -1.0900 -5.2900 5.8800 147 | -0.0700 -5.5200 5.9100 148 | 0.9300 -5.4100 5.9100 149 | -1.2500 -3.5300 12.1000 150 | -1.1000 -4.0600 11.4100 151 | -3.7200 -0.4800 16.9700 152 | 5.0100 -2.7400 5.6800 153 | -0.2500 -2.2700 13.0100 154 | -2.2200 -0.4800 12.6000 155 | -3.2900 -4.2900 5.9100 156 | -2.3200 -4.0400 5.8900 157 | -1.0900 -5.3600 6.0200 158 | -0.0600 -5.5900 6.0500 159 | 0.9300 -5.5100 6.0600 160 | -1.9700 -3.2500 12.0800 161 | -2.1000 -2.9600 12.2100 162 | 4.1100 -2.7900 5.8300 163 | 5.1000 -2.6800 5.8200 164 | 1.4800 -3.7800 11.2700 165 | -1.9900 -0.6800 12.7000 166 | -3.4800 -4.4200 6.0600 167 | -2.5200 -3.9400 6.0300 168 | 3.4000 -1.7300 11.7000 169 | -0.3600 -5.6500 6.2000 170 | 0.6400 -5.6300 6.2000 171 | 0.1800 -3.8100 11.9700 172 | -0.6300 -3.6800 12.1000 173 | 4.3600 -2.2400 9.7200 174 | 5.0100 -2.7100 5.9700 175 | 1.7800 -3.7300 11.2600 176 | 1.7800 -2.8100 12.4800 177 | -3.8800 -4.4300 6.2000 178 | -2.9000 -4.1300 6.1800 179 | 1.7200 -1.2700 12.8900 180 | -0.6600 -5.6000 6.3300 181 | 0.3400 -5.6600 6.3400 182 | 1.5600 -3.5000 11.8200 183 | 0.4800 -3.7500 11.9700 184 | -3.5100 -0.6900 12.7200 185 | 4.6000 -2.6300 6.1100 186 | 2.1700 -3.5800 11.2600 187 | 1.6100 -1.7900 12.9300 188 | -2.7300 -0.3400 12.4700 189 | -3.4700 -4.4700 6.3500 190 | -2.5100 -4.0000 6.3100 191 | -4.4900 -1.5700 13.2800 192 | -0.3600 -5.6400 6.4700 193 | 0.6400 -5.6300 6.4800 194 | -7.1200 -5.2500 14.2800 195 | -1.7100 -3.9600 11.4100 196 | -9.2400 -2.3400 12.2800 197 | 5.1900 -2.5500 6.2500 198 | 0.3900 -1.8800 13.1200 199 | -4.9300 -3.8100 6.4200 200 | -3.7700 -4.4800 6.4800 201 | -2.8000 -4.1400 6.4600 202 | 3.6700 -1.8100 11.3600 203 | -0.6700 -5.5500 6.6000 204 | 0.3500 -5.6600 6.6200 205 | 1.3300 -5.4100 6.6000 206 | -1.5400 -3.6000 11.9500 207 | -4.4800 -3.2400 12.0700 208 | 4.3100 -2.6100 6.3800 209 | 5.2900 -2.4600 6.3800 210 | 0.9200 -2.0200 13.0700 211 | -4.6000 -4.1000 6.5800 212 | -3.5700 -4.5100 6.6300 213 | -2.6000 -4.0900 6.6000 214 | 4.7200 -2.0800 6.8500 215 | -0.4600 -5.6000 6.7500 216 | 0.5400 -5.6100 6.7500 217 | 1.5200 -5.3200 6.7400 218 | 0.7400 -2.6800 12.8700 219 | -4.8900 -1.5700 14.4700 220 | 4.4800 -2.3700 6.5100 221 | 5.4800 -2.3300 6.5100 222 | 0.8100 -2.0000 13.0900 223 | -6.9900 -2.6300 6.4600 224 | -3.5700 -4.5100 6.7700 225 | -2.6000 -4.1300 6.7400 226 | -1.2700 -5.5200 6.8700 227 | -0.2600 -5.6400 6.8900 228 | 0.7400 -5.5400 6.8900 229 | 0.3100 -1.4400 13.1700 230 | -9.1800 -2.1300 12.6900 231 | 2.3000 -1.9800 12.5800 232 | 5.1700 -2.3200 6.6500 233 | 1.7500 -2.2500 12.7800 234 | -5.6500 -5.0100 3.6200 235 | -3.3700 -4.4900 6.9100 236 | -2.4000 -4.2100 6.8900 237 | -1.0600 -5.6100 7.0200 238 | -0.0500 -5.7600 7.0400 239 | 0.9400 -5.5200 7.0300 240 | 1.9600 -3.4700 11.6800 241 | -0.2100 -3.9100 11.8300 242 | -8.5900 -4.4800 13.7900 243 | 4.9600 -2.2000 6.7800 244 | -5.4900 -3.0900 6.1300 245 | -8.3600 -3.2400 15.2200 246 | -3.4700 -4.5100 7.0500 247 | -2.4900 -4.2100 7.0300 248 | -1.1700 -5.6300 7.1600 249 | -0.1400 -5.8300 7.1800 250 | 0.8400 -5.5500 7.1700 251 | 0.0000 -4.0000 11.6900 252 | -0.4100 -3.8800 11.8300 253 | -8.3900 -1.1700 10.8900 254 | 5.1500 -2.0900 6.9100 255 | -5.3400 -1.3100 15.8600 256 | -4.2700 -4.5400 7.1900 257 | -3.2700 -4.5100 7.1900 258 | -0.6400 -3.1700 12.5300 259 | -0.8600 -5.6700 7.3100 260 | 0.1600 -5.8700 7.3300 261 | 1.1400 -5.5700 7.3100 262 | 0.6000 -4.0000 11.5500 263 | -3.6700 -3.3600 11.9400 264 | 4.6200 -1.4200 9.1800 265 | 4.5600 -0.6200 9.4600 266 | 3.4400 -2.5800 11.3400 267 | -5.4700 -4.6000 7.3200 268 | -4.4700 -4.5700 7.3300 269 | -3.4700 -4.5200 7.3300 270 | -2.4900 -4.3100 7.3200 271 | -1.1600 -5.6800 7.4400 272 | -0.1400 -5.8700 7.4600 273 | 0.8400 -5.5900 7.4500 274 | -1.3100 -3.9300 11.5400 275 | -7.0600 -5.9200 11.9000 276 | 3.2800 -1.9800 11.8100 277 | 4.5000 -0.9300 9.7300 278 | 1.2400 -2.9500 12.6300 279 | -5.8700 -4.6100 7.4600 280 | -4.8600 -4.6700 7.4800 281 | -3.8600 -4.6300 7.4800 282 | -2.8800 -4.3600 7.4600 283 | -1.5400 -1.5100 12.8600 284 | -0.7500 -5.7900 7.5900 285 | 0.2600 -5.8800 7.6100 286 | 1.2400 -5.5500 7.5900 287 | -3.0600 -3.4900 11.6600 288 | -3.8700 -3.3500 11.9400 289 | -5.8300 -4.8600 3.5800 290 | 4.1600 -1.0600 10.5600 291 | -1.5700 -0.6500 12.8100 292 | -5.1600 -4.7400 7.6200 293 | -4.1600 -4.6000 7.6200 294 | -3.1700 -4.4800 7.6100 295 | -1.5600 -5.6500 7.7200 296 | -0.5400 -5.8400 7.7400 297 | 0.4600 -5.8100 7.7400 298 | 1.4300 -5.4600 7.7200 299 | -2.2600 -3.5000 11.6700 300 | -7.3700 -5.8900 12.4600 301 | -8.5800 -0.7900 9.5400 302 | 0.5600 -1.3700 13.1700 303 | -5.8600 -4.7200 7.7500 304 | -4.8500 -4.7600 7.7700 305 | -3.8600 -4.6600 7.7600 306 | -2.8800 -4.3900 7.7500 307 | -1.5500 -5.7300 7.8600 308 | -0.5400 -5.8600 7.8800 309 | 0.4600 -5.7800 7.8800 310 | 1.4300 -5.4400 7.8600 311 | -2.1500 -3.5600 11.6700 312 | 4.0100 -1.5700 10.8400 313 | -1.6800 -0.4800 12.7400 314 | -7.4800 -4.1500 10.0800 315 | -5.9500 -4.7800 7.9000 316 | -4.9500 -4.8400 7.9100 317 | -3.9600 -4.6200 7.9000 318 | -2.9800 -4.4300 7.8900 319 | -8.7500 -1.7100 10.1000 320 | -0.6400 -5.8600 8.0100 321 | 0.3500 -5.7600 8.0100 322 | 1.3300 -5.4300 8.0000 323 | -2.3600 -3.4700 11.6600 324 | -6.9100 -5.4000 14.0100 325 | -7.7000 -4.3100 14.9800 326 | -0.0700 -2.8900 12.8000 327 | -6.2600 -4.7900 8.0500 328 | -5.2400 -4.9300 8.0500 329 | -4.2600 -4.7300 8.0500 330 | -3.2600 -4.6200 8.0500 331 | -8.3500 -2.9500 15.3000 332 | -0.9500 -5.8000 8.1500 333 | 0.0500 -5.7600 8.1500 334 | 1.0400 -5.5500 8.1400 335 | -2.1500 -3.6600 11.5400 336 | -0.9700 -3.0800 12.5300 337 | -8.7600 -2.5900 15.1600 338 | -7.0000 -2.9900 15.6000 339 | -2.3900 -2.1400 12.4700 340 | -5.3400 -4.9000 8.1900 341 | -4.3500 -4.7900 8.1900 342 | -3.3600 -4.6800 8.1900 343 | -8.5200 -1.3800 10.6300 344 | -1.2400 -5.9000 8.2900 345 | -0.2500 -5.7900 8.2900 346 | 0.7500 -5.6800 8.2900 347 | 4.1900 -0.3500 10.4200 348 | -2.4600 -0.2700 12.4900 349 | -6.8600 -5.9800 12.1800 350 | -6.1600 -3.5000 15.4700 351 | -0.0100 -4.5300 10.1100 352 | -5.3400 -4.9000 8.3300 353 | -4.3400 -4.8400 8.3300 354 | -3.3500 -4.6900 8.3300 355 | -8.7300 -1.6100 10.0900 356 | -1.1400 -5.8400 8.4300 357 | -0.1500 -5.7300 8.4200 358 | 0.8500 -5.6800 8.4300 359 | -8.7100 -1.3900 11.3100 360 | -2.4700 -3.3500 11.8000 361 | -7.0200 -0.8600 15.5800 362 | 1.5500 -1.6400 12.9600 363 | -6.0400 -4.9800 8.4700 364 | -5.0300 -4.9800 8.4800 365 | -4.0500 -4.7100 8.4700 366 | -3.0700 -4.5600 8.4600 367 | -0.2200 -0.6000 13.0800 368 | -0.7500 -5.8100 8.5700 369 | 0.2500 -5.7300 8.5700 370 | 1.2400 -5.5400 8.5600 371 | 2.2800 -4.8700 8.5200 372 | -3.5400 -3.6600 11.5300 373 | -8.8500 -4.5100 12.7000 374 | -2.3300 -0.3000 12.5300 375 | -5.7400 -4.9900 8.6200 376 | -4.7300 -4.9900 8.6200 377 | -3.7600 -4.6100 8.6000 378 | -2.7700 -4.5200 8.6000 379 | 0.4800 -0.8000 13.1600 380 | -0.6500 -5.7600 8.7000 381 | 0.3500 -5.6800 8.7000 382 | 1.3300 -5.4900 8.6900 383 | 2.3700 -4.7800 8.6500 384 | 3.1000 -2.3400 11.8800 385 | -7.6400 -4.0200 10.0700 386 | -9.1700 -3.1400 12.6900 387 | -5.6300 -5.0300 8.7600 388 | -4.6300 -4.9800 8.7600 389 | -3.6600 -4.6300 8.7400 390 | -2.6500 -4.6300 8.7500 391 | 1.5700 -1.0900 12.9500 392 | -0.5500 -5.7500 8.8400 393 | 0.4400 -5.6400 8.8400 394 | 1.4300 -5.4000 8.8300 395 | 2.4700 -4.7100 8.7900 396 | -2.0600 -0.9400 12.7100 397 | 0.7600 -1.8400 13.1300 398 | -8.9100 -4.0200 12.5600 399 | -5.6300 -5.0400 8.9000 400 | -4.6400 -4.9500 8.9000 401 | -3.6600 -4.6200 8.8800 402 | -2.6600 -4.6300 8.8900 403 | 2.1100 -1.2400 12.7200 404 | -0.4500 -5.7600 8.9800 405 | 0.5400 -5.5900 8.9800 406 | 1.5200 -5.3200 8.9600 407 | 2.6600 -4.6300 8.9300 408 | 4.4800 -1.5300 9.7300 409 | 2.4300 -2.1600 12.4700 410 | -0.1700 -4.6300 10.0800 411 | -6.0300 -5.0200 9.0400 412 | -5.0400 -4.9600 9.0400 413 | -4.0600 -4.6600 9.0300 414 | -3.0500 -4.7100 9.0400 415 | 2.4500 -1.3300 12.5300 416 | -0.9500 -5.7400 9.1200 417 | 0.0500 -5.6700 9.1200 418 | 1.0300 -5.4100 9.1100 419 | -6.6600 -5.9000 11.7600 420 | -6.6500 -4.9200 14.5600 421 | -6.6400 -5.0300 14.4200 422 | 2.5300 -1.7700 12.4700 423 | -6.6600 -4.7900 9.1600 424 | -5.6300 -5.0400 9.1800 425 | -4.6500 -4.8500 9.1800 426 | -3.6600 -4.6000 9.1700 427 | -2.6500 -4.6600 9.1800 428 | 2.9200 -1.4600 12.1700 429 | -0.5600 -5.6800 9.2600 430 | 0.4400 -5.5500 9.2500 431 | 1.4100 -5.2000 9.2300 432 | 2.3600 -4.5900 9.2000 433 | -7.3800 -5.6400 13.7200 434 | -3.7600 -0.3400 12.7400 435 | 1.1500 -2.9300 12.6600 436 | -6.7600 -4.7800 9.3000 437 | -5.7300 -5.0200 9.3200 438 | -4.7500 -4.8300 9.3200 439 | -3.7700 -4.5800 9.3100 440 | -2.7500 -4.7000 9.3200 441 | 3.8100 -1.7100 11.1500 442 | -0.6600 -5.6300 9.3900 443 | 0.3300 -5.5300 9.3900 444 | 1.3000 -5.1500 9.3700 445 | 2.2600 -4.5800 9.3400 446 | -7.4800 -5.6300 13.7200 447 | -5.5400 -3.9500 14.8200 448 | 3.8500 -2.1300 11.0100 449 | -6.4500 -4.8100 9.4500 450 | -5.4400 -4.9800 9.4600 451 | -4.4400 -4.8700 9.4600 452 | -3.4600 -4.6400 9.4500 453 | -2.4500 -4.7400 9.4700 454 | 0.9800 -3.0200 12.6200 455 | -0.3700 -5.5100 9.5300 456 | 0.6200 -5.3900 9.5300 457 | 1.5800 -4.9500 9.4900 458 | 2.5500 -4.5300 9.4800 459 | -0.2500 -3.4700 12.3700 460 | -0.0400 -5.2600 9.7800 461 | 1.3300 -1.3000 13.0400 462 | -6.4600 -4.8000 9.5900 463 | -5.4400 -4.9000 9.6000 464 | -4.4400 -4.8500 9.6000 465 | -3.4600 -4.6000 9.5900 466 | -2.4500 -4.7100 9.6000 467 | 0.4400 -5.2300 9.7700 468 | -0.3800 -5.4000 9.6600 469 | 0.6100 -5.2900 9.6600 470 | 1.5800 -4.8400 9.6300 471 | 2.5500 -4.4900 9.6200 472 | 0.5300 -1.5000 13.1700 473 | -6.5500 -2.2600 15.6300 474 | -8.6300 -2.8000 10.1000 475 | -6.1600 -4.7700 9.7300 476 | -5.1500 -4.7900 9.7400 477 | -4.1600 -4.6800 9.7300 478 | -3.1600 -4.6200 9.7300 479 | -2.1600 -4.6200 9.7400 480 | -1.1200 -5.0100 9.7700 481 | 0.3100 -5.2400 9.7800 482 | 1.2700 -4.8300 9.7700 483 | 2.2500 -4.5300 9.7600 484 | -4.0800 -3.1500 12.0700 485 | -7.1600 -5.9100 13.1700 486 | -2.2000 -2.7600 12.2700 487 | -6.3600 -4.7400 9.8700 488 | -5.3500 -4.7800 9.8800 489 | -4.3600 -4.7100 9.8800 490 | -3.3700 -4.5500 9.8700 491 | -2.3600 -4.5800 9.8800 492 | 1.0300 -2.7500 12.7900 493 | -7.2500 -3.0900 6.9100 494 | 1.3700 -4.7200 9.9100 495 | 2.3500 -4.4700 9.9000 496 | -1.8500 -1.1400 12.7700 497 | 0.4000 -2.4500 12.9900 498 | -0.3100 -1.0000 13.1100 499 | -6.2600 -4.7200 10.0100 500 | -5.2500 -4.7900 10.0200 501 | -4.2600 -4.6100 10.0100 502 | -3.2700 -4.5200 10.0100 503 | -2.2600 -4.6100 10.0200 504 | -1.2600 -4.5200 10.0300 505 | -8.9400 -1.3100 11.7300 506 | 0.8500 -4.5800 10.0300 507 | 1.8600 -4.6000 10.0400 508 | 3.7100 -2.3700 11.1000 509 | -1.8000 -1.0100 12.7800 510 | -0.6700 -0.9000 13.0400 511 | -6.0600 -4.7400 10.1500 512 | -5.0600 -4.7000 10.1600 513 | -4.0700 -4.5800 10.1500 514 | -3.0700 -4.4600 10.1500 515 | -2.0600 -4.5800 10.1600 516 | -1.0600 -4.4800 10.1600 517 | -8.5800 -2.7900 10.2300 518 | 1.0600 -4.5400 10.1700 519 | 2.0500 -4.4900 10.1800 520 | 0.7600 -3.5300 12.1000 521 | -6.4600 -5.9000 12.1800 522 | 1.3700 -1.5900 13.0300 523 | -6.8900 -4.4200 10.2700 524 | -5.8600 -4.6900 10.2900 525 | -4.8700 -4.5600 10.2900 526 | -3.8700 -4.4900 10.2900 527 | -2.8800 -4.4300 10.2900 528 | -1.8600 -4.5400 10.3000 529 | -0.8600 -4.4700 10.3000 530 | 0.1300 -4.4000 10.3100 531 | 1.1500 -4.4500 10.3000 532 | 2.1400 -4.3600 10.3100 533 | 4.5800 -1.8200 9.3100 534 | -8.2300 -3.0600 10.7700 535 | 0.0700 -2.6400 12.9200 536 | -6.5900 -4.4600 10.4100 537 | -5.5700 -4.6400 10.4300 538 | -4.5800 -4.4400 10.4200 539 | -3.5900 -4.2900 10.4200 540 | -2.5800 -4.3800 10.4300 541 | -1.5700 -4.4500 10.4400 542 | -0.5600 -4.4300 10.4400 543 | 0.4300 -4.3400 10.4400 544 | 1.4400 -4.3700 10.4400 545 | -8.8900 -1.1100 11.9900 546 | -0.5100 -1.2200 13.0700 547 | 0.4400 -1.7600 13.1400 548 | -6.9000 -4.3600 10.5500 549 | -5.8800 -4.5500 10.5600 550 | -4.8800 -4.4700 10.5700 551 | -3.8800 -4.4100 10.5700 552 | -2.8900 -4.2700 10.5700 553 | -1.8700 -4.4100 10.5800 554 | -0.8700 -4.4100 10.5800 555 | 0.1300 -4.4200 10.5900 556 | 1.1100 -4.1300 10.5700 557 | 2.1200 -4.1300 10.5800 558 | -0.0400 -0.9300 13.1300 559 | -5.5100 -4.1100 11.3900 560 | -6.9000 -4.3600 10.6900 561 | -5.8800 -4.4700 10.7000 562 | -4.8800 -4.4200 10.7100 563 | -3.8900 -4.3400 10.7100 564 | -2.9000 -4.2000 10.7000 565 | -1.8800 -4.3400 10.7200 566 | -0.8700 -4.4000 10.7200 567 | 0.1300 -4.3800 10.7300 568 | 1.1100 -4.0500 10.7100 569 | 2.1000 -3.9900 10.7100 570 | 4.4000 -0.6400 10.0100 571 | 1.2500 -1.9800 13.0200 572 | -6.7000 -4.3300 10.8300 573 | -5.6900 -4.3800 10.8400 574 | -4.6900 -4.2800 10.8400 575 | -3.7000 -4.1500 10.8400 576 | -2.7000 -4.1300 10.8400 577 | -1.6800 -4.2900 10.8500 578 | -0.6700 -4.3700 10.8600 579 | 0.3200 -4.2900 10.8600 580 | 1.3000 -3.9300 10.8500 581 | 2.2900 -3.7900 10.8500 582 | -4.9200 -3.9400 11.3900 583 | -6.9400 -3.4400 15.5100 584 | -6.1100 -4.3300 10.9800 585 | -5.1000 -4.2500 10.9700 586 | -4.1000 -4.2000 10.9800 587 | -3.1100 -4.0100 10.9800 588 | -2.1000 -4.1600 10.9900 589 | -1.0800 -4.3100 11.0000 590 | -0.0700 -4.3100 11.0000 591 | 0.9100 -4.1000 11.0000 592 | 1.9900 -3.8200 10.9800 593 | 2.8500 -2.1300 12.1600 594 | -6.8100 -1.3400 15.5600 595 | -5.6100 -4.1800 11.1100 596 | -4.6100 -4.1200 11.1200 597 | -3.6200 -3.9600 11.1200 598 | -2.6200 -3.9200 11.1100 599 | -1.5900 -4.1600 11.1300 600 | -0.5800 -4.2900 11.1400 601 | 0.4200 -4.2300 11.1400 602 | 1.3900 -3.8300 11.1300 603 | 2.3700 -3.5800 11.1200 604 | 4.1500 -0.0500 10.4300 605 | 4.0600 -1.8700 10.7000 606 | -5.4100 -4.0900 11.2500 607 | -4.4200 -3.9800 11.2500 608 | -3.4300 -3.8200 11.2500 609 | -2.4300 -3.8300 11.2500 610 | -4.5900 -1.9700 13.5100 611 | -4.7800 -3.7700 11.9800 612 | -2.8000 -0.7400 12.5300 613 | -0.8700 -5.1700 3.7800 614 | 0.1900 -4.7300 3.8300 615 | 1.3400 -4.4100 3.8900 616 | 2.3300 -4.0300 3.9400 617 | -5.6400 -4.4600 12.9700 618 | -4.8100 -5.0800 3.6100 619 | -4.1900 -1.5100 12.9400 620 | -1.5300 -5.4800 3.9000 621 | -0.5900 -5.0400 3.9300 622 | 0.3800 -4.6600 3.9800 623 | 1.4600 -4.4000 4.0400 624 | 2.4300 -4.0000 4.0800 625 | 2.9400 -2.8900 4.0300 626 | -5.1300 -5.1600 3.7200 627 | -4.1100 -4.8400 3.7700 628 | -2.0700 -5.6200 4.0100 629 | -1.0600 -5.2600 4.0600 630 | -0.1000 -4.8600 4.1000 631 | 2.2600 -3.2100 11.9300 632 | 2.2800 -4.1400 4.2200 633 | 4.0000 -3.1200 9.5500 634 | -5.3200 -3.6000 14.3900 635 | -4.7000 -5.0700 3.8900 636 | 0.5500 -4.8200 9.9800 637 | -1.1500 -5.3100 4.1900 638 | -0.2100 -4.8900 4.2300 639 | -4.9400 -4.0500 12.2700 640 | 2.1900 -4.1900 4.3600 641 | 2.9100 -3.4800 4.3500 642 | -6.1500 -4.4600 11.2400 643 | -5.4500 -3.7500 14.9600 644 | -4.0600 -4.7500 4.0500 645 | -1.6400 -5.5100 4.3100 646 | -4.5700 -3.0900 13.1000 647 | -8.9500 -4.7300 12.0200 648 | 2.3500 -4.0600 4.5000 649 | 3.0600 -3.3500 4.4900 650 | -6.2200 -4.8600 13.8300 651 | -4.5400 -1.2400 15.5000 652 | -3.9800 -4.6900 4.1900 653 | -1.5600 -5.4500 4.4500 654 | -4.1700 -1.0600 15.5100 655 | -6.5500 -5.4100 13.5500 656 | 2.0400 -4.1600 4.6200 657 | 2.8800 -3.6100 4.6300 658 | 3.4900 -2.7800 4.6100 659 | 4.6200 -2.5700 4.6800 660 | 5.2600 -1.7800 4.6600 661 | 2.5200 -3.8400 10.6000 662 | -5.9900 -4.3500 14.6800 663 | 3.2100 -3.4200 10.6100 664 | 3.3600 -3.2800 10.6100 665 | 2.1200 -4.1100 4.7600 666 | 2.9700 -3.5600 4.7700 667 | 3.4900 -3.1300 10.6100 668 | 4.7700 -2.6000 4.8200 669 | 5.4000 -1.7900 4.8000 670 | -4.3700 -1.1400 15.5100 671 | -5.6100 -3.8700 13.8100 672 | 4.0700 -0.0600 10.5600 673 | 4.1200 -0.3600 10.5600 674 | 2.0900 -4.2200 4.9000 675 | 2.9000 -3.6300 4.9100 676 | 4.1400 -2.9800 9.4100 677 | 4.7500 -2.7300 4.9700 678 | 5.4200 -1.9700 4.9600 679 | 3.0400 -3.3700 11.0100 680 | -6.3000 -4.9200 14.1100 681 | -2.7500 -0.2700 15.9600 682 | -5.5500 -3.9500 14.9700 683 | 2.0800 -4.3700 5.0500 684 | 2.8200 -3.7000 5.0500 685 | 3.5600 -3.0200 5.0500 686 | 4.7000 -2.8300 5.1100 687 | 5.4200 -2.1300 5.1100 688 | -9.2500 -2.7400 12.1500 689 | -6.9300 -5.7300 13.4000 690 | -3.7900 -0.4200 16.0900 691 | -6.7200 -5.3500 13.9700 692 | 2.1600 -4.4600 5.2000 693 | 2.8700 -3.7600 5.2000 694 | 3.6200 -3.0900 5.2000 695 | 4.8100 -2.8100 5.2600 696 | 5.5500 -2.1300 5.2600 697 | -4.8500 -0.9700 14.3100 698 | -6.8400 -5.6800 13.4100 699 | -3.7500 -0.4600 15.0700 700 | 1.7200 -4.8800 5.3500 701 | 2.5500 -4.3200 5.3600 702 | 3.2600 -3.6000 5.3500 703 | 2.3500 -3.1600 11.9400 704 | 5.1500 -2.6000 5.4000 705 | 5.8200 -1.8400 5.3900 706 | 4.5300 -0.7200 9.6000 707 | -3.8100 -0.8700 15.6600 708 | -5.0500 -4.0700 12.6900 709 | 1.5300 -5.1200 5.4900 710 | 2.3800 -4.5800 5.5000 711 | 3.0700 -3.8500 5.4900 712 | 3.7600 -3.1100 5.4900 713 | 3.1700 -3.0500 11.2800 714 | 5.6300 -2.2300 5.5400 715 | 1.6500 -3.2600 12.1900 716 | -5.9200 -4.2800 14.8200 717 | -6.0400 -4.4400 13.6700 718 | -4.6100 -3.5000 12.6900 719 | 2.2100 -4.6800 5.6400 720 | 2.9600 -4.0300 5.6400 721 | 3.7000 -3.3500 5.6400 722 | -4.5500 -3.4100 12.4000 723 | 5.7600 -2.0800 5.6700 724 | -5.4500 -4.5200 12.1200 725 | -4.6900 -3.4100 13.1100 726 | -5.2600 -3.6600 13.6700 727 | 1.7000 -5.0200 5.7700 728 | 2.5800 -4.5100 5.7800 729 | 3.2900 -3.8000 5.7800 730 | 3.9400 -3.0200 5.7700 731 | -6.2200 -4.8600 13.6800 732 | 5.7800 -2.1000 5.8100 733 | 4.5300 -0.8200 9.6000 734 | -4.4200 -1.0700 15.7900 735 | -5.9800 -4.6700 13.1100 736 | 2.7700 -3.5100 11.0100 737 | 1.8400 -4.8800 5.9000 738 | 2.7200 -4.3700 5.9200 739 | 3.4800 -3.7200 5.9200 740 | 4.0700 -2.8600 5.9000 741 | -8.9600 -4.2300 12.1500 742 | 5.9000 -1.9400 5.9400 743 | 4.2000 -2.5700 9.8000 744 | 4.6600 -1.1100 8.7600 745 | -8.9600 -3.7200 12.1500 746 | 1.2900 -5.3100 6.0300 747 | 2.1300 -4.7500 6.0400 748 | 2.9700 -4.1900 6.0500 749 | 3.7400 -3.5600 6.0600 750 | 4.2800 -2.6400 6.0300 751 | 5.4400 -2.4800 6.0900 752 | 6.0700 -1.6700 6.0700 753 | -6.6800 -5.2500 14.1100 754 | -9.2300 -2.7400 12.0100 755 | -6.8300 -4.3000 7.5700 756 | 1.5500 -5.1500 6.1700 757 | 2.4200 -4.6300 6.1900 758 | 3.2100 -4.0200 6.1900 759 | 3.9400 -3.3300 6.1900 760 | -5.8300 -4.7000 12.8300 761 | 5.6700 -2.2900 6.2200 762 | -4.4000 -1.0900 14.9200 763 | -6.0800 -5.1900 11.5700 764 | -5.1800 -3.4500 13.8200 765 | 1.2700 -5.4400 6.3100 766 | 2.0900 -4.8600 6.3200 767 | 2.8800 -4.2500 6.3200 768 | 3.6900 -3.6700 6.3300 769 | 4.2500 -2.7600 6.3100 770 | 5.5800 -2.3400 6.3500 771 | 4.0900 -2.2800 10.4600 772 | 1.2500 -3.7100 11.6400 773 | -5.7500 -4.1700 14.2500 774 | 2.2700 -4.1600 10.4700 775 | 2.1000 -4.8800 6.4500 776 | 2.8800 -4.2500 6.4600 777 | 3.7000 -3.6700 6.4700 778 | 4.2600 -2.7900 6.4400 779 | -6.0000 -4.3300 13.8200 780 | 6.0200 -1.7700 6.4800 781 | -5.5900 -4.0500 14.6800 782 | -4.0100 -0.6200 15.9400 783 | 3.4000 -3.1700 10.7400 784 | 1.8200 -5.1600 6.5900 785 | 2.5700 -4.5000 6.5900 786 | 3.3700 -3.9000 6.6000 787 | 4.0900 -3.2000 6.5900 788 | -6.3500 -5.4700 11.4200 789 | 5.8300 -2.0100 6.6200 790 | 1.8800 -4.7900 9.5300 791 | 3.0500 -4.1700 9.5600 792 | 4.6200 -0.6200 9.1800 793 | -6.2900 -5.7100 11.7200 794 | 2.1400 -4.9200 6.7300 795 | 2.8600 -4.2300 6.7200 796 | 3.6800 -3.6600 6.7300 797 | 4.2800 -2.8000 6.7200 798 | 3.0900 -4.2000 9.4200 799 | 6.0700 -1.5200 6.7300 800 | 3.7900 -3.4900 9.5500 801 | -6.2600 -4.8100 14.2500 802 | 2.0800 -3.1500 12.0600 803 | 1.5600 -5.3200 6.8500 804 | 2.3900 -4.7600 6.8600 805 | 3.1100 -4.0600 6.8600 806 | 3.9000 -3.4500 6.8700 807 | 4.4100 -2.4800 6.8300 808 | 5.8700 -1.7600 6.8700 809 | -5.2600 -4.2800 11.8400 810 | -5.4600 -3.7400 14.5300 811 | -6.7700 -5.4500 13.8300 812 | 1.5700 -5.3400 6.9900 813 | 2.4100 -4.7800 7.0000 814 | 3.1000 -4.0500 6.9900 815 | 3.8900 -3.4400 7.0000 816 | 4.4200 -2.5000 6.9700 817 | 2.2700 -3.3800 11.6600 818 | -6.2400 -5.7700 12.0000 819 | -3.8100 -0.3900 16.3800 820 | 1.7100 -3.3300 12.0600 821 | 1.5800 -5.3400 7.1200 822 | 2.4400 -4.8200 7.1400 823 | 3.1200 -4.0700 7.1300 824 | 3.9000 -3.4500 7.1400 825 | 4.4400 -2.5200 7.1100 826 | 2.0500 -4.8300 9.2700 827 | 2.9100 -3.6800 10.4700 828 | -6.2000 -5.2000 12.9800 829 | -4.6000 -3.5200 12.5500 830 | 3.2900 -3.9800 9.5600 831 | 2.0900 -5.0200 7.2700 832 | 2.8800 -4.4200 7.2700 833 | 3.6200 -3.7300 7.2700 834 | 4.2500 -2.9300 7.2600 835 | -8.9000 -2.1100 13.5100 836 | 4.2100 -2.4200 9.9300 837 | -3.2200 -0.3300 15.5100 838 | 3.0000 -3.6300 10.4700 839 | 4.6400 -0.5100 8.9000 840 | 1.8800 -5.2400 7.4000 841 | 2.7000 -4.6700 7.4100 842 | 3.4200 -3.9700 7.4100 843 | 4.0900 -3.2000 7.4000 844 | 4.5700 -2.2200 7.3700 845 | -4.9300 -3.7400 13.1100 846 | -3.4500 -0.5100 15.5100 847 | 2.8900 -3.3400 11.1400 848 | -8.7100 -3.3900 13.5100 849 | -5.4100 -3.6500 15.1100 850 | 2.1600 -5.1100 7.5400 851 | 2.9400 -4.4800 7.5500 852 | 3.6600 -3.7800 7.5500 853 | 4.2600 -2.9400 7.5300 854 | 4.6800 -1.8700 7.4800 855 | 3.0600 -3.2300 11.1400 856 | -5.3800 -3.6700 13.9600 857 | -4.7900 -3.4500 13.2500 858 | -5.4200 -3.9400 13.5300 859 | 4.4000 -1.0400 10.0100 860 | 2.2700 -5.0900 7.6800 861 | 3.0100 -4.4200 7.6800 862 | 3.7400 -3.7200 7.6800 863 | 4.3100 -2.8500 7.6600 864 | 4.7200 -1.7600 7.6100 865 | 3.1400 -3.1700 11.1400 866 | -5.7800 -4.2900 13.3900 867 | -5.1600 -3.3000 14.1000 868 | -4.9500 -4.0300 12.1200 869 | 4.4800 0.3700 8.8900 870 | 2.0100 -5.2400 7.8100 871 | 2.8300 -4.6700 7.8200 872 | 3.5500 -3.9800 7.8200 873 | 4.1700 -3.1400 7.8100 874 | 4.6200 -2.1200 7.7700 875 | 4.1600 -0.7600 10.5600 876 | -5.8300 -4.0700 13.9600 877 | 4.4200 0.0700 9.5900 878 | -5.5500 -4.2500 13.2500 879 | -5.9900 -5.1500 11.7100 880 | 1.5700 -5.3500 7.9300 881 | 2.5000 -4.9100 7.9500 882 | 3.2400 -4.2300 7.9500 883 | 3.9300 -3.4900 7.9500 884 | 4.4500 -2.5500 7.9200 885 | 4.7500 -1.3200 7.8600 886 | -0.2400 -4.4100 10.2400 887 | 3.8400 -3.2300 9.8100 888 | -5.2000 -3.4200 14.3900 889 | -4.6000 -1.3100 14.9200 890 | -6.4600 -5.8200 11.7200 891 | 2.0600 -5.1500 8.0800 892 | 2.9100 -4.6100 8.0900 893 | 3.6300 -3.9100 8.0900 894 | 4.2300 -3.0700 8.0700 895 | 4.6600 -2.0100 8.0400 896 | 3.7000 -3.2300 10.0800 897 | 2.5000 -4.1300 10.3400 898 | 4.2200 -1.3500 10.4200 899 | -7.6200 -5.4300 11.4900 900 | -5.3900 -4.2800 11.6900 901 | 1.8300 -5.1800 8.2000 902 | 2.7400 -4.7300 8.2300 903 | 3.4600 -4.0200 8.2200 904 | 4.1000 -3.2300 8.2100 905 | 4.6000 -2.2300 8.1800 906 | -4.4200 -3.1000 12.2500 907 | -5.0200 -3.6400 13.3900 908 | 2.5600 -4.3600 9.9500 909 | 2.6900 -3.2600 11.4000 910 | -5.2400 -4.3100 12.6900 911 | 1.6400 -5.2700 8.3300 912 | 2.5600 -4.8200 8.3600 913 | 3.2700 -4.1100 8.3500 914 | 3.9700 -3.3900 8.3500 915 | 4.5100 -2.4600 8.3200 916 | 2.7200 -4.3900 9.6900 917 | -9.1300 -3.3400 12.4200 918 | 3.5300 -3.1700 10.4800 919 | -3.7700 -0.4500 16.5300 920 | -5.1800 -4.2300 12.6900 921 | 1.3100 -5.5100 8.4600 922 | 2.1500 -4.9500 8.4800 923 | 3.0300 -4.4500 8.4900 924 | 3.7500 -3.7400 8.4900 925 | 4.3300 -2.8800 8.4700 926 | -7.4400 -4.0900 10.3500 927 | 2.9000 -3.9900 10.0800 928 | -4.6600 -3.5900 12.4000 929 | -3.2400 -0.4600 15.6600 930 | -4.2800 -0.9300 15.9400 931 | 1.5700 -5.3500 8.6000 932 | -5.9600 -5.3300 12.1400 933 | 3.2000 -4.1900 8.6200 934 | 3.9300 -3.4900 8.6200 935 | 4.4500 -2.5500 8.5900 936 | 2.6500 -4.4700 9.5500 937 | -3.8800 -0.6200 15.0700 938 | 3.3800 -3.7800 9.8200 939 | -4.3000 -1.0600 15.0700 940 | -4.7800 -3.7700 12.5500 941 | -5.7300 -4.2000 14.5400 942 | 1.6600 -5.3000 8.7400 943 | -6.2800 -4.9300 11.2600 944 | 3.2700 -4.1100 8.7500 945 | 3.9800 -3.4000 8.7500 946 | 4.4800 -2.4300 8.7200 947 | 3.8600 -3.1000 9.9500 948 | -5.6800 -4.7300 12.4100 949 | -5.5100 -3.8400 15.1100 950 | -4.4700 -3.0500 12.8200 951 | -5.1900 -4.3700 12.4100 952 | 1.7400 -5.2400 8.8700 953 | -4.5000 -3.3200 12.4000 954 | 3.3500 -4.0600 8.8900 955 | 4.0400 -3.3100 8.8800 956 | 4.5000 -2.3000 8.8500 957 | 2.6000 -4.2400 10.0800 958 | -5.1300 -4.1200 11.8400 959 | -9.0300 -3.5300 12.1500 960 | -5.8700 -4.9700 12.5500 961 | -6.8700 -5.6400 13.5400 962 | 1.9500 -5.0300 9.0100 963 | 2.9100 -4.4600 9.0300 964 | 3.6900 -3.8400 9.0300 965 | 4.2300 -2.9300 9.0100 966 | 2.0100 -4.7900 9.4000 967 | -8.5400 -1.0800 11.3000 968 | -5.6000 -4.6600 12.4100 969 | -6.4700 -5.8100 12.5700 970 | -5.6400 -3.9900 14.2500 971 | 4.6700 -0.8100 8.6200 972 | 1.9400 -5.0100 9.1400 973 | 2.8900 -4.4400 9.1600 974 | 3.6700 -3.8100 9.1600 975 | 4.2200 -2.9100 9.1400 976 | -5.3500 -3.5600 14.1000 977 | -5.1000 -2.7900 14.4700 978 | -8.6800 -1.2100 9.5500 979 | 2.6500 -3.3600 11.2700 980 | -5.6100 -3.8700 14.2400 981 | 1.3700 -3.3800 12.1800 982 | 2.4600 -3.6200 3.7500 983 | 4.1700 -0.2600 3.9400 984 | 2.5800 -3.6200 3.8900 985 | -8.5600 -0.9900 10.0800 986 | 4.3800 -0.0400 4.1100 987 | 2.6500 -3.7100 4.0500 988 | -4.6800 -2.4600 13.5500 989 | 4.7900 -0.2100 4.2900 990 | -9.0000 -1.4200 12.0000 991 | -4.8300 -1.1700 13.8600 992 | 5.2000 -0.8700 4.4600 993 | 4.8500 0.1000 4.4500 994 | -5.1200 -3.2000 14.1600 995 | 5.3800 -1.1600 4.6200 996 | 5.1900 -0.1700 4.6100 997 | -5.0200 -2.2900 14.7800 998 | -4.6400 -2.2400 13.5600 999 | 5.5700 -0.9400 4.7900 1000 | 5.2800 0.0400 4.7700 1001 | -5.0500 -2.3900 14.7800 1002 | 5.5900 -1.6400 4.9200 1003 | 5.6900 -0.6300 4.9400 1004 | 5.2300 0.3300 4.9100 1005 | -8.4600 -2.9800 11.1700 1006 | -4.9100 -2.6800 13.8500 1007 | 5.8100 -0.7100 5.0900 1008 | 5.4200 0.2500 5.0600 1009 | -6.9000 -2.6800 6.4200 1010 | -4.7800 -1.2600 13.7100 1011 | 5.9100 -1.2100 5.2400 1012 | 5.7700 -0.2200 5.2300 1013 | 4.2900 -1.0500 10.2900 1014 | -4.7900 -1.1600 13.7100 1015 | 5.9700 -1.1000 5.3800 1016 | 5.7900 -0.1100 5.3700 1017 | -4.8000 -0.9600 13.5500 1018 | -4.9200 -2.9800 13.7000 1019 | 5.9800 -1.6100 5.5200 1020 | 5.9900 -0.6000 5.5300 1021 | 5.5400 0.3600 5.4900 1022 | -4.6900 -1.7600 13.7100 1023 | -5.1800 -2.6000 15.2400 1024 | 6.0600 -0.6900 5.6700 1025 | 5.6600 0.2700 5.6400 1026 | -5.1000 -2.5900 14.6200 1027 | -9.2200 -2.1400 12.2800 1028 | 6.1200 -0.6900 5.8200 1029 | 5.7000 0.2800 5.7800 1030 | -8.7200 -4.8800 11.5500 1031 | 4.6100 -1.1200 9.3200 1032 | 6.1600 -0.9800 5.9600 1033 | 5.9400 0.0000 5.9400 1034 | -8.3200 -1.1500 14.6000 1035 | -8.7900 -2.0200 9.5600 1036 | 6.1400 -1.2900 6.0900 1037 | 6.0900 -0.2900 6.0900 1038 | -9.2100 -2.4400 11.8800 1039 | -9.1600 -2.9400 11.8800 1040 | -4.7500 -1.5600 13.8600 1041 | 6.1900 -1.0800 6.2300 1042 | 6.0100 -0.0900 6.2300 1043 | 4.6200 -0.5200 9.1800 1044 | -7.1100 -2.3000 6.4300 1045 | 6.1700 -1.2900 6.3700 1046 | 6.0800 -0.2900 6.3700 1047 | -8.7100 -1.4100 9.2800 1048 | -8.9400 -4.7300 12.1600 1049 | -7.6900 -3.1400 7.3900 1050 | 6.1900 -0.8800 6.5100 1051 | 5.8600 0.1000 6.4900 1052 | -8.1400 -0.8300 14.7300 1053 | -9.1200 -3.1400 11.8800 1054 | -4.7100 -2.0600 13.7100 1055 | 6.1500 -1.2900 6.6500 1056 | 6.0200 -0.2900 6.6400 1057 | -8.7500 -3.6100 11.6000 1058 | -3.0700 -5.0600 3.7500 1059 | -4.7000 -1.9600 13.7100 1060 | 6.0900 -1.3900 6.7800 1061 | 6.0400 -0.3900 6.7800 1062 | -8.8400 -4.6100 12.7000 1063 | -7.1500 -2.5300 6.5600 1064 | -8.6700 -3.2300 11.4100 1065 | 6.0800 -1.0900 6.9200 1066 | 5.8500 -0.1000 6.9100 1067 | -9.2000 -2.0400 12.0100 1068 | -9.1900 -2.7400 11.8800 1069 | -4.7500 -1.7600 13.8600 1070 | 6.0100 -0.8800 7.0600 1071 | -7.9800 -3.4400 10.9000 1072 | -8.7800 -0.8000 12.1300 1073 | -6.1500 -4.7000 7.8300 1074 | -4.7300 -1.2600 13.5600 1075 | -8.5200 -2.3900 10.6400 1076 | -8.8900 -1.1100 12.1300 1077 | -5.1800 -3.1000 14.6200 1078 | 4.6500 -1.0200 8.9000 1079 | -8.5000 -2.4900 10.6400 1080 | -8.9300 -3.7200 12.0100 1081 | 4.6500 -1.6200 8.9000 1082 | -5.0600 -2.4900 14.9300 1083 | -8.7900 -0.9000 11.9900 1084 | -8.7300 -3.1900 13.9300 1085 | 4.6200 -1.9200 8.8900 1086 | -8.5400 -1.0900 10.2200 1087 | -7.2900 -2.4000 6.6900 1088 | 4.4600 0.3700 7.4900 1089 | 4.5700 -1.2200 9.4600 1090 | -5.0100 -1.9800 14.9300 1091 | 4.3800 -0.4400 10.0100 1092 | 4.5900 -2.0200 8.8900 1093 | 4.5800 0.0800 7.6400 1094 | -8.9600 -4.0200 12.0200 1095 | 4.5600 -2.1300 8.8900 1096 | 4.2600 -0.3500 10.2900 1097 | 4.7500 -1.0100 7.7900 1098 | 4.6100 -0.0200 7.7800 1099 | -8.4400 -2.5800 10.7700 1100 | -4.9300 -2.2800 14.1600 1101 | -8.9000 -1.2100 12.5400 1102 | 4.7300 -0.8100 7.9300 1103 | 4.5500 0.1800 7.9200 1104 | -4.6600 -1.5500 13.5600 1105 | -4.6300 -1.3500 13.4100 1106 | -8.8800 -2.4000 13.7800 1107 | 4.7100 -1.8100 8.0600 1108 | 4.7200 -0.8100 8.0600 1109 | 4.5500 0.1800 8.0600 1110 | -8.7700 -2.6200 9.3000 1111 | -5.0700 -2.2900 14.4700 1112 | 4.7100 -1.7100 8.2000 1113 | 4.7100 -0.7100 8.2000 1114 | 4.5000 0.2800 8.1900 1115 | -8.9600 -4.4300 12.0200 1116 | -4.9200 -0.8700 14.1700 1117 | 4.6900 -1.8100 8.3400 1118 | 4.6900 -0.8100 8.3400 1119 | 4.5100 0.1700 8.3300 1120 | -8.9600 -4.5300 12.0200 1121 | -5.0600 -2.7900 14.3200 1122 | 4.6900 -1.7100 8.4800 1123 | 4.6800 -0.7100 8.4800 1124 | 4.4700 0.2700 8.4700 1125 | -7.3000 -4.6800 14.8400 1126 | -8.9400 -4.5200 12.2900 1127 | -3.4800 -2.8600 12.3600 1128 | -1.0700 -2.0600 12.9100 1129 | -6.5100 -3.5500 15.4900 1130 | -7.5900 -4.3100 15.0100 1131 | -7.2400 -3.8000 15.3600 1132 | -4.4700 -1.1400 13.1100 1133 | -8.6200 -1.3800 13.9100 1134 | 2.1900 -2.5100 12.4300 1135 | 0.2200 -5.0300 9.9300 1136 | -6.4400 -2.2900 15.6300 1137 | -7.7100 -1.9600 15.5300 1138 | -8.1700 -2.5600 15.4200 1139 | -0.8700 -5.1900 9.7500 1140 | -0.1800 -4.9200 9.9900 1141 | -8.6000 -2.4600 15.2500 1142 | -0.9600 -5.3200 9.6500 1143 | -8.0700 -3.0200 15.3900 1144 | -4.8700 -3.3300 13.4700 1145 | -8.1500 -3.3600 11.0300 1146 | -0.0700 -4.6600 10.0600 1147 | -2.0800 -1.7900 12.6600 1148 | -6.6700 -4.0900 15.2600 1149 | -7.9100 -2.2000 15.5100 1150 | -1.7700 -2.7300 12.4100 1151 | -3.1300 -2.9600 12.1900 1152 | -7.4900 -4.1900 15.1200 1153 | 1.2600 -2.2600 12.9500 1154 | -2.4500 -1.6900 12.5800 1155 | -2.5700 -1.6600 12.5700 1156 | -7.2000 -3.9600 15.3000 1157 | -4.4200 -1.4500 13.1400 1158 | 1.9000 -2.5700 12.5700 1159 | -8.6000 -1.5800 14.0500 1160 | -6.7800 -3.6200 15.4600 1161 | -8.4800 -2.3800 10.9100 1162 | 1.0200 -2.3300 12.9900 1163 | -8.4700 -1.6400 15.1700 1164 | -2.5600 -1.9500 12.5200 1165 | 0.5100 -2.2000 13.0700 1166 | -8.8800 -3.8200 11.7400 1167 | -6.6200 -1.5400 15.5700 1168 | -6.2800 -4.1900 15.1700 1169 | -9.1100 -1.8300 12.8200 1170 | -6.4600 -3.1300 15.6000 1171 | -8.9200 -4.1200 11.7500 1172 | -7.6100 -1.5600 15.5100 1173 | -8.7900 -1.8200 9.5600 1174 | -8.7500 -2.1100 10.1000 1175 | -4.1700 -3.1100 12.0900 1176 | -1.0800 -1.7700 12.9600 1177 | -6.4200 -3.5700 15.4600 1178 | -8.4800 -2.4800 10.9100 1179 | -7.3700 -4.2200 15.1400 1180 | 0.0900 -3.5000 12.3200 1181 | -2.0900 -1.5000 12.7100 1182 | -8.7600 -1.8100 10.1000 1183 | -2.7800 -2.6100 12.2300 1184 | -2.6800 -3.0700 12.0000 1185 | -2.8200 -1.3100 12.5700 1186 | -8.4300 -1.1600 14.1800 1187 | -4.6700 -2.6600 13.4900 1188 | 0.1700 -3.3800 12.4000 1189 | 3.6000 0.3100 11.0500 1190 | -8.5600 -1.3900 10.4900 1191 | -7.2400 -1.6600 15.5800 1192 | -8.6500 -3.0100 9.2900 1193 | -3.9800 -0.9900 12.8700 1194 | 5.5400 -0.3100 7.2300 1195 | -0.2300 -4.7700 10.0500 1196 | -4.5400 -0.8400 13.0500 1197 | -3.3300 -1.7400 12.7200 1198 | -8.7700 -1.7100 9.4200 1199 | -8.8500 -2.2000 13.7800 1200 | -8.6000 -1.8900 15.1700 1201 | -6.7000 -1.9400 15.6200 1202 | -5.2600 -2.6000 15.3600 1203 | 5.9600 -0.5700 7.0500 1204 | -9.2300 -2.9400 12.5600 1205 | -2.9800 -1.5500 12.6100 1206 | -2.8900 -2.4400 12.3700 1207 | 3.5400 0.0400 11.2800 1208 | 2.8000 0.2400 11.9600 1209 | -8.8900 -3.0000 14.3400 1210 | -5.8100 -1.0400 15.7300 1211 | 1.6200 -2.3500 12.8000 1212 | -7.7400 -2.1000 15.5400 1213 | 5.6100 -0.6200 7.3000 1214 | -6.5400 -4.5700 14.8900 1215 | -5.1700 -1.7800 15.3500 1216 | 3.9300 -0.2000 10.8300 1217 | 3.2700 -0.0300 11.6800 1218 | 2.4600 0.1900 12.2200 1219 | -8.6200 -2.9000 9.9700 1220 | -2.6600 -1.9200 12.5200 1221 | -0.3200 -1.8300 13.0800 1222 | -0.4400 -1.8000 13.0700 1223 | 5.0300 -0.6000 7.3100 1224 | -3.0100 -2.7000 12.2800 1225 | -5.2500 -2.8900 15.3200 1226 | 3.7300 -0.2900 11.1500 1227 | 3.0200 -0.1000 11.9000 1228 | 2.2000 0.1200 12.4300 1229 | -8.5500 -0.9800 11.4400 1230 | -3.8200 -1.6100 12.8200 1231 | -4.6100 -2.3900 13.4700 1232 | -3.1400 -1.7900 12.6600 1233 | 5.9100 -0.9900 7.1600 1234 | 4.9000 -0.7000 7.3200 1235 | -7.4800 -3.7400 15.3400 1236 | -4.3800 -2.7500 12.8100 1237 | 3.6500 -0.4100 11.2700 1238 | 2.9400 -0.2200 12.0100 1239 | 2.1100 0.0100 12.5300 1240 | -8.6100 -4.1800 14.0700 1241 | -5.1300 -2.2200 15.2000 1242 | -8.6700 -2.5900 15.2100 1243 | -3.2900 -2.4700 12.5000 1244 | -4.0400 -2.5700 12.4800 1245 | 5.4200 -1.0000 7.3600 1246 | -3.3500 -1.4500 12.7400 1247 | -4.1500 -1.9600 12.8200 1248 | 3.9600 -0.6300 10.8800 1249 | 3.3000 -0.4600 11.7400 1250 | 2.5200 -0.2400 12.3300 1251 | 1.6500 0.0000 12.7600 1252 | -8.7800 -2.2100 9.9700 1253 | -8.3600 -2.6600 15.3600 1254 | -3.2300 -2.0600 12.6300 1255 | -4.1100 -1.5300 12.9000 1256 | -0.6800 -1.7400 13.0300 1257 | 5.1700 -1.0700 7.3600 1258 | -0.2300 -3.1300 12.6300 1259 | 0.6200 -3.0700 12.6300 1260 | 3.7500 -0.7200 11.1900 1261 | 3.0700 -0.5300 11.9800 1262 | 2.2600 -0.3100 12.5200 1263 | 1.3600 -0.0600 12.9000 1264 | -8.4300 -2.9800 10.3600 1265 | -3.4900 -1.5600 12.7600 1266 | -8.4400 -1.9200 15.2800 1267 | 1.7700 -2.6700 12.6000 1268 | 5.7300 -1.3700 7.2300 1269 | 4.7700 -1.1000 7.5000 1270 | -7.3400 -1.0600 15.5200 1271 | -4.7100 -3.2300 13.2800 1272 | 3.5400 -0.8000 11.4800 1273 | 2.8200 -0.6000 12.2000 1274 | 1.9800 -0.3700 12.6900 1275 | 1.0400 -0.1100 12.9900 1276 | -8.4800 -2.8800 10.3600 1277 | -6.6400 -1.6700 15.5900 1278 | -5.9100 -2.0000 15.5900 1279 | -3.4700 -2.4200 12.5800 1280 | -5.8700 -3.0000 15.5400 1281 | 5.4900 -1.4500 7.2800 1282 | -9.2200 -2.5400 11.8800 1283 | -1.0600 -3.2000 12.4400 1284 | 0.3500 -2.2900 13.0400 1285 | 3.3200 -0.8800 11.7700 1286 | 2.5600 -0.6700 12.4000 1287 | 1.6900 -0.4300 12.8400 1288 | 0.7100 -0.1600 13.0400 1289 | -8.8900 -4.6200 12.5600 1290 | -8.5700 -2.7600 15.2400 1291 | -6.1200 -1.9500 15.6000 1292 | 0.6400 -4.8500 9.9500 1293 | -3.6000 -2.6800 12.4700 1294 | 5.2400 -1.5200 7.2700 1295 | -2.5400 -2.3900 12.3300 1296 | -3.9300 -2.1600 12.6900 1297 | 3.8900 -1.1700 11.0300 1298 | 3.2300 -0.9900 11.8700 1299 | 2.4600 -0.7800 12.4900 1300 | 1.5800 -0.5400 12.9100 1301 | 0.5700 -0.2600 13.0700 1302 | -8.5200 -2.5900 10.5000 1303 | -1.0600 -2.3400 12.8500 1304 | -8.1200 -3.6000 15.1900 1305 | -1.6400 -1.7700 12.8100 1306 | -2.0200 -1.6600 12.7000 1307 | 4.9200 -1.5700 7.1500 1308 | -1.0200 -5.0100 9.8000 1309 | -4.0700 -1.7000 12.8600 1310 | 3.7500 -1.2700 11.2400 1311 | 3.0600 -1.0800 12.0400 1312 | 2.2700 -0.8700 12.6100 1313 | 1.3700 -0.6200 12.9900 1314 | 0.3400 -0.3400 13.1000 1315 | -9.2100 -2.2400 12.5500 1316 | -9.1800 -2.8400 12.8300 1317 | 0.4800 -4.9600 9.9400 1318 | -2.0400 -5.1800 9.0500 1319 | -4.1800 -2.9700 12.2000 1320 | 5.2000 -1.7900 7.1300 1321 | -4.4400 -1.7300 13.2400 1322 | -7.6900 -0.6900 15.3800 1323 | 3.9200 -1.4600 11.0000 1324 | 3.2600 -1.2800 11.8500 1325 | 2.5000 -1.0700 12.4800 1326 | 1.6300 -0.8300 12.9200 1327 | 0.6500 -0.5600 13.1300 1328 | -0.5300 -0.2400 12.9800 1329 | -8.6400 -2.0000 10.5000 1330 | -6.7600 -0.6500 15.5300 1331 | -7.7000 -3.1100 15.4900 1332 | -3.7900 -2.7800 12.3900 1333 | 5.4100 -1.9900 6.9800 1334 | -7.2200 -4.5500 14.9400 1335 | 1.0100 -3.3100 12.3900 1336 | -0.5300 -2.6200 12.8800 1337 | 3.4500 -1.4700 11.6500 1338 | 2.7100 -1.2600 12.3400 1339 | 1.8700 -1.0300 12.8200 1340 | 0.9300 -0.7800 13.1200 1341 | -0.1900 -0.4700 13.0800 1342 | -6.1300 -2.3200 3.4600 1343 | -6.1200 -4.6000 3.6500 1344 | -5.1300 -5.1500 3.6600 1345 | -7.1100 -1.4400 3.5300 1346 | -6.4000 -2.1600 3.5600 1347 | -6.3900 -3.6900 3.7200 1348 | -5.9800 -4.7500 3.8000 1349 | -7.7100 -5.5600 11.7500 1350 | -3.2100 -4.8900 3.6600 1351 | -2.1200 -5.6100 3.6700 1352 | -7.1700 -1.3600 3.6700 1353 | -6.4800 -2.0900 3.7000 1354 | -6.3400 -3.4700 3.8300 1355 | -6.0100 -4.6200 3.9300 1356 | -8.0000 -3.5000 10.6000 1357 | -3.3000 -4.8300 3.8000 1358 | -2.5500 -5.4900 3.8200 1359 | -7.9600 -4.7300 14.4700 1360 | -7.0200 -1.4900 3.8200 1361 | -6.2800 -2.1600 3.8400 1362 | -6.2500 -3.7000 3.9900 1363 | -5.8700 -4.7700 4.0700 1364 | -6.6200 -4.5800 7.9100 1365 | -3.3000 -4.8300 3.9400 1366 | -2.5400 -5.4800 3.9600 1367 | -8.9100 -4.8300 12.2800 1368 | -7.0700 -0.8100 3.8800 1369 | -6.6100 -1.7700 3.9600 1370 | -5.8300 -2.4000 3.9700 1371 | -6.0700 -4.3900 4.1900 1372 | -5.3300 -5.0600 4.2100 1373 | -3.4100 -4.6500 4.0700 1374 | -2.7100 -5.3600 4.1000 1375 | -7.5800 -3.9400 10.4800 1376 | -7.9200 -3.9100 9.6700 1377 | -7.0300 -1.1900 4.0600 1378 | -6.3600 -1.9300 4.1000 1379 | -6.9800 -4.6500 9.5500 1380 | -5.9200 -4.5000 4.3300 1381 | -2.2100 -4.8100 7.5100 1382 | -3.2600 -4.7700 4.2100 1383 | -2.4800 -5.3900 4.2300 1384 | -8.1700 -5.1500 13.7900 1385 | -6.9600 -4.6200 9.6900 1386 | -6.8900 -1.0100 4.1900 1387 | -6.2900 -1.8500 4.2300 1388 | -6.7900 -4.7400 9.5500 1389 | -5.7600 -4.6200 4.4700 1390 | -7.1400 -4.3600 10.0800 1391 | -2.9400 -5.0100 4.3600 1392 | -1.6700 -5.5200 9.0600 1393 | -6.9200 -4.1900 7.4900 1394 | -7.3100 -4.4600 8.6000 1395 | -6.6900 -1.3900 4.3600 1396 | -5.8500 -1.9400 4.3600 1397 | -8.4800 -5.4100 12.1600 1398 | -7.8600 -5.7500 12.4400 1399 | -3.2400 -4.5800 4.4800 1400 | -1.7100 -5.4000 9.2000 1401 | -2.3400 -4.9200 8.9100 1402 | -0.9600 -4.6500 9.9800 1403 | -2.0800 -4.9100 9.3200 1404 | -6.1100 -1.6300 4.4900 1405 | -8.6100 -3.0400 9.0900 1406 | -5.6400 -4.3200 4.7100 1407 | -7.7000 -5.8600 13.1300 1408 | -2.8900 -4.7800 4.6100 1409 | -8.3000 -5.0000 13.7900 1410 | -6.6200 -4.7300 8.3300 1411 | -7.9300 -5.0100 14.2000 1412 | -6.0800 -1.4400 4.6100 1413 | -5.2300 -1.9700 4.6100 1414 | -5.3900 -4.1400 4.8200 1415 | -7.4100 -4.4200 8.7400 1416 | -2.9100 -4.6600 4.7500 1417 | -8.8600 -3.3200 14.5700 1418 | -7.1600 -4.1600 7.7700 1419 | -7.5800 -5.6000 11.9000 1420 | -1.9000 -5.6600 8.2500 1421 | -5.4000 -1.7100 4.7300 1422 | -8.3100 -3.2600 10.3200 1423 | -7.5300 -5.5500 11.6300 1424 | -3.0300 -4.3200 4.8600 1425 | -2.1000 -4.6100 9.5800 1426 | -8.5900 -5.2200 12.5600 1427 | -8.2500 -4.6100 14.3300 1428 | -8.5200 -3.2400 9.3700 1429 | -5.6200 -1.3500 4.8500 1430 | -2.3500 -4.5200 7.3500 1431 | -4.7100 -3.9900 5.0600 1432 | -6.9900 -4.6700 9.4200 1433 | -2.4200 -4.6800 5.0000 1434 | -8.1500 -3.5900 8.8400 1435 | -7.8000 -5.6900 12.3100 1436 | -2.0000 -5.1800 7.5300 1437 | -5.6400 -1.2100 4.9800 1438 | -4.9300 -1.9200 5.0100 1439 | -4.8400 -3.6600 5.1700 1440 | -7.6500 -5.5600 11.7600 1441 | -2.6200 -4.2900 5.1100 1442 | -8.7600 -3.5100 14.5800 1443 | -8.0700 -5.6700 12.9900 1444 | -8.2400 -4.7600 14.2000 1445 | -1.7800 -5.6600 8.6600 1446 | -5.1400 -1.7000 5.1400 1447 | -6.3700 -4.9000 8.4700 1448 | -8.3600 -5.0700 13.5100 1449 | -7.8900 -4.3200 14.8700 1450 | -8.2200 -3.3100 10.4500 1451 | -7.8000 -5.8400 12.5800 1452 | -8.7200 -5.0900 11.7500 1453 | -7.9800 -5.5600 13.4000 1454 | -8.2700 -3.2700 8.5500 1455 | -4.9100 -1.8900 5.2900 1456 | -4.7500 -3.7000 5.4400 1457 | -7.2300 -4.5100 8.6100 1458 | -2.3700 -3.9900 5.3600 1459 | -7.1500 -4.5800 8.7400 1460 | -8.4900 -3.2100 8.9600 1461 | -8.8200 -3.4200 14.5700 1462 | -2.4300 -4.8900 8.3500 1463 | -4.9900 -1.8200 5.4300 1464 | -8.3700 -3.2300 8.6900 1465 | -4.2500 -4.1900 5.6000 1466 | -7.0100 -4.4400 8.0500 1467 | -1.8500 -4.6100 5.5300 1468 | -7.0000 -4.6800 9.2800 1469 | -7.7300 -3.8900 8.0400 1470 | -8.6200 -3.0200 9.7700 1471 | -1.7800 -5.6900 7.9700 1472 | -5.0900 -1.7800 5.5700 1473 | -4.9600 -3.1700 5.6800 1474 | -4.4100 -4.0700 5.7400 1475 | -2.0100 -5.3100 8.9200 1476 | -1.9800 -4.4400 5.6600 1477 | -1.2900 -5.1800 5.6900 1478 | -8.1700 -5.4700 13.2500 1479 | -8.1300 -3.6800 9.7900 1480 | -7.9100 -3.8900 9.8000 1481 | -7.5300 -4.2300 9.5400 1482 | -5.0700 -2.6800 5.7900 1483 | -4.6900 -3.7700 5.8600 1484 | -8.0200 -3.6100 8.1600 1485 | -2.2400 -4.1300 5.7800 1486 | -1.6000 -4.9300 5.8200 1487 | -0.7100 -5.4200 5.8300 1488 | -8.3100 -4.6900 14.1900 1489 | -1.2600 -4.5200 10.1200 1490 | -5.3000 -2.7900 5.9400 1491 | -4.7600 -3.6900 5.9900 1492 | -4.0000 -4.3500 6.0200 1493 | -2.0600 -4.9500 7.3800 1494 | -1.7300 -4.7700 5.9500 1495 | -0.8600 -5.4300 5.9700 1496 | -7.7900 -5.3200 13.9400 1497 | -7.8200 -5.8500 12.7200 1498 | -5.1300 -3.2000 6.1000 1499 | -4.5000 -4.0000 6.1500 1500 | -1.9500 -5.1300 7.3800 1501 | -2.1300 -4.3000 6.0700 1502 | -1.4900 -5.0900 6.1100 1503 | -7.7800 -4.0500 9.5400 1504 | -1.8000 -5.6900 8.5300 1505 | -1.9900 -5.1200 9.1900 1506 | -5.0200 -3.5300 6.2600 1507 | -4.2800 -4.2100 6.2900 1508 | -2.2700 -5.1700 8.3700 1509 | -1.9300 -4.5300 6.2200 1510 | -1.2900 -5.3100 6.2600 1511 | -8.6800 -3.2400 14.9800 1512 | -8.0300 -4.0200 15.0000 1513 | -8.4000 -3.4000 9.5100 1514 | -1.5700 -4.7600 9.7100 1515 | -4.0400 -4.3900 6.4400 1516 | -2.1500 -4.3100 6.3500 1517 | -1.5200 -5.1200 6.3900 1518 | -7.1700 -4.5800 9.1500 1519 | -8.0100 -5.2700 13.8000 1520 | -6.2800 -4.9200 9.1500 1521 | -2.1300 -5.3000 8.6500 1522 | -8.5200 -4.7900 13.5100 1523 | -8.1400 -5.6100 12.9800 1524 | -2.1700 -4.3400 6.5000 1525 | -1.5600 -5.1700 6.5400 1526 | -8.5800 -3.1500 9.3600 1527 | -7.8100 -3.6800 7.8900 1528 | -2.0100 -4.9900 9.3200 1529 | -1.4200 -5.3600 9.4700 1530 | -4.2700 -4.3400 6.7100 1531 | -8.6200 -3.0500 9.2200 1532 | -1.8400 -4.8700 6.6600 1533 | -8.3400 -5.3800 12.8400 1534 | -8.8200 -5.0500 12.0200 1535 | -6.9000 -4.7200 9.4200 1536 | -8.1900 -3.4900 8.7000 1537 | -2.4100 -4.8800 8.0700 1538 | -8.5600 -3.7200 14.7200 1539 | -1.9900 -4.7400 6.8000 1540 | -1.3200 -5.4900 6.8300 1541 | -8.2300 -3.4900 10.0600 1542 | -7.8100 -5.8400 12.9900 1543 | -6.9600 -4.5300 8.1900 1544 | -7.5200 -5.6800 12.0400 1545 | -8.4200 -4.9900 13.5100 1546 | -8.3800 -3.3500 9.9200 1547 | -1.7300 -5.2000 6.9600 1548 | -8.5800 -3.1400 9.5000 1549 | -8.0800 -3.6700 8.7100 1550 | -5.7800 -0.8700 15.8000 1551 | -7.3200 -4.2700 10.0800 1552 | -1.6100 -5.7900 8.1100 1553 | -1.9500 -5.5700 7.9700 1554 | -2.2800 -4.4400 7.0600 1555 | -1.7000 -5.3100 7.1100 1556 | -1.8100 -5.7100 8.1100 1557 | -7.2500 -4.5400 8.8800 1558 | -6.4600 -4.7100 8.0500 1559 | -2.1000 -5.4300 8.3800 1560 | -5.4500 -1.5900 5.7000 1561 | -8.0300 -4.8100 14.3400 1562 | -8.1400 -5.4300 13.3900 1563 | -2.0800 -4.8200 7.2300 1564 | -1.4000 -5.5700 7.2600 1565 | -7.7900 -3.2800 7.6300 1566 | -9.0000 -3.4200 12.9700 1567 | -8.8400 -3.9100 12.9700 1568 | -9.0400 -2.6300 11.4700 1569 | -5.8000 -2.6900 3.9900 1570 | -4.9900 -0.4400 16.5600 1571 | -6.9100 -0.7700 4.2200 1572 | -5.6400 -2.3700 4.1100 1573 | -6.1700 -3.4200 4.1800 1574 | -8.6800 -2.2000 10.3700 1575 | -8.8600 -1.2000 13.0900 1576 | -5.8700 -3.0900 4.2900 1577 | -6.1100 -4.1200 4.3300 1578 | -8.9300 -4.3200 12.4200 1579 | -9.1500 -2.6300 12.9600 1580 | -5.4500 -2.7500 4.3800 1581 | -6.0500 -3.8100 4.4600 1582 | -8.7700 -3.0900 13.9300 1583 | -6.4100 -0.8300 4.5800 1584 | -8.8700 -3.2000 14.7500 1585 | -5.2600 -2.7400 4.5000 1586 | -5.9000 -3.8000 4.5800 1587 | -8.8800 -3.6100 13.1000 1588 | -6.1500 -0.9100 4.7000 1589 | -4.9700 -2.3100 4.6100 1590 | -5.5000 -3.3600 4.6700 1591 | -5.1400 -0.5500 16.4100 1592 | -5.8400 -0.6700 4.8100 1593 | -8.8400 -3.4000 14.4800 1594 | -5.0900 -2.9200 4.7700 1595 | -5.4300 -3.9500 4.8100 1596 | -5.7500 -0.5700 4.9400 1597 | -8.9500 -2.4000 14.4700 1598 | -4.9300 -2.5000 4.8900 1599 | -5.1000 -3.5200 4.9100 1600 | -5.7200 -0.6600 5.0800 1601 | -8.9800 -2.4100 14.3300 1602 | -4.9900 -2.8100 5.0400 1603 | -8.8500 -4.1100 12.8300 1604 | -5.6100 -1.0600 5.2100 1605 | -4.9600 -2.7100 5.1700 1606 | -8.9200 -1.3100 12.8100 1607 | -8.8200 -3.4000 14.2000 1608 | -4.9700 -2.8100 5.3200 1609 | 4.5100 0.3100 6.7100 1610 | -5.4500 -1.3500 5.4800 1611 | -4.9300 -2.5000 5.4500 1612 | -4.8500 -3.5000 5.4500 1613 | -5.6600 -0.7600 5.6300 1614 | -5.1600 -1.7200 5.6000 1615 | -8.9900 -1.6100 13.2300 1616 | -8.6100 -1.5800 14.7400 1617 | -5.7000 -0.8600 5.7700 1618 | -8.8200 -2.0000 13.6400 1619 | -9.0400 -2.6200 13.2400 1620 | -5.7500 -0.5600 5.9000 1621 | -8.8800 -3.4100 13.2400 1622 | -8.7300 -2.0800 15.1500 1623 | -8.6600 -4.2900 13.2400 1624 | -8.6600 -4.4900 13.2400 1625 | -8.3000 -1.2500 15.1400 1626 | -5.7400 -0.8100 15.8400 1627 | -8.6500 -4.1900 13.6600 1628 | -5.7300 -0.9100 15.8500 1629 | -7.5200 -1.3200 6.7600 1630 | -8.8700 -2.8000 13.9200 1631 | -7.5800 -1.2200 6.8900 1632 | -8.5600 -1.5700 14.4700 1633 | -7.8300 -1.5400 7.0600 1634 | -8.9600 -2.5000 14.8800 1635 | -7.9400 -1.2500 7.2000 1636 | -7.9200 -2.2500 7.2100 1637 | -8.8000 -3.1900 14.8900 1638 | -7.9000 -0.8400 7.3200 1639 | -8.0400 -1.8600 7.3500 1640 | -5.2700 -4.2500 6.8500 1641 | -8.6100 -1.6800 15.0100 1642 | -8.1300 -1.5700 7.4900 1643 | -7.9400 -2.5600 7.4800 1644 | -8.8600 -3.1100 13.3800 1645 | -8.2700 -1.1800 7.6300 1646 | -8.1300 -2.1700 7.6300 1647 | -8.1900 -0.8400 14.5900 1648 | -8.1900 -0.7700 7.7500 1649 | -8.3200 -1.7800 7.7800 1650 | -7.9800 -3.0600 7.7600 1651 | -8.8900 -2.3000 15.0200 1652 | -8.4100 -1.2900 7.9100 1653 | -8.4000 -2.2900 7.9200 1654 | -8.0200 -3.2600 7.9000 1655 | -8.3700 -1.0800 8.0400 1656 | -8.5100 -2.1000 8.0600 1657 | -8.1300 -3.0700 8.0500 1658 | -8.9000 -2.6000 15.0200 1659 | -8.4500 -1.2900 8.1800 1660 | -8.5000 -2.3000 8.2000 1661 | -8.1700 -3.2700 8.1900 1662 | -9.2000 -2.0400 12.4100 1663 | -8.5200 -1.6000 8.3300 1664 | -8.4500 -2.5900 8.3400 1665 | -8.6500 -4.3900 13.3800 1666 | -8.7800 -2.9900 15.0200 1667 | -8.6000 -1.5000 8.4700 1668 | -8.5000 -2.5000 8.4700 1669 | -8.6200 -4.5900 13.3800 1670 | -8.5200 -1.4700 14.8800 1671 | -8.6400 -1.0000 8.6000 1672 | -8.6700 -2.0100 8.6100 1673 | -8.4600 -2.9900 8.6100 1674 | -8.9500 -2.7100 14.6100 1675 | -9.1600 -3.2400 12.5600 1676 | -8.7400 -1.5200 8.7500 1677 | -8.6700 -2.5100 8.7500 1678 | -8.0800 -0.8200 14.8700 1679 | -8.5600 -0.9700 13.7700 1680 | -8.7400 -1.2100 8.8700 1681 | -8.7500 -2.2200 8.8900 1682 | -8.8900 -2.9000 14.0600 1683 | -8.9700 -2.5100 14.7500 1684 | -8.6500 -1.0100 9.0000 1685 | -8.8100 -2.0200 9.0200 1686 | -8.6300 -3.0000 9.0200 1687 | -8.8700 -3.0000 14.8900 1688 | -8.6500 -1.1000 9.1400 1689 | -8.8200 -2.1200 9.1600 1690 | -8.6600 -1.7800 14.0500 1691 | -8.9100 -2.3000 14.6100 1692 | -9.0400 -1.5200 12.6800 1693 | 5.6500 0.2500 6.7500 1694 | 5.4800 -0.1400 7.1600 1695 | 5.7400 0.2100 6.7000 1696 | -6.1300 -0.9200 15.4800 1697 | -6.1200 -0.7800 15.4200 1698 | 4.7500 0.1600 6.9300 1699 | 4.6900 -0.2900 7.4700 1700 | 5.4700 0.2900 6.8000 1701 | 4.6800 -0.0200 7.1500 1702 | -8.4600 -3.0700 11.2000 1703 | -8.3100 -5.1200 11.3200 1704 | -4.7400 -0.6800 13.2100 1705 | 4.7400 0.2500 6.8200 1706 | -4.6700 -0.5300 12.9600 1707 | -1.0100 -0.2500 12.8800 1708 | 0.1000 0.0000 12.9900 1709 | 1.1200 0.0200 12.9300 1710 | -1.9100 -0.3800 12.6600 1711 | -2.2300 -0.3200 12.5600 1712 | -2.7800 -0.2900 12.4400 1713 | 5.0800 0.1000 7.0300 1714 | -6.4200 -3.8000 6.8000 1715 | -7.1300 -0.6900 3.8300 1716 | -8.6500 -5.0400 11.5800 1717 | -7.4100 -2.9900 7.0000 1718 | -5.2600 -5.1100 3.5800 1719 | -6.0800 -4.5200 7.4300 1720 | -4.5400 -4.2500 6.7500 1721 | -7.4900 -3.6000 7.4900 1722 | -5.0400 -4.4000 7.1100 1723 | -7.7200 -5.1600 11.1500 1724 | -7.0100 -5.2700 11.1300 1725 | -6.2700 -2.9100 6.2400 1726 | -7.4000 -1.3000 6.6500 1727 | -6.6300 -2.6800 6.2500 1728 | -5.6900 -3.0500 6.1600 1729 | 1.7300 0.1300 3.4300 1730 | 2.8800 0.2300 3.7000 1731 | 1.4700 -0.0400 3.4200 1732 | 2.5300 -0.1000 3.4800 1733 | 3.7300 0.1000 3.8600 1734 | 1.1100 -0.1600 3.4400 1735 | 2.1400 -0.2800 3.4400 1736 | 3.2600 -0.2400 3.6200 1737 | 0.2700 -0.1900 3.5100 1738 | 1.3200 -0.2700 3.5500 1739 | 2.3000 -0.4800 3.4400 1740 | 3.4100 -0.4500 3.6100 1741 | -8.8400 -3.1400 11.5000 1742 | 0.6000 -0.4600 3.4500 1743 | 2.4500 -0.6900 3.4300 1744 | 3.5700 -0.6400 3.6300 1745 | -7.6300 -5.2700 11.2400 1746 | -0.0900 -0.2000 3.8600 1747 | 0.8400 -0.5100 3.6300 1748 | 3.0400 -0.8900 3.4900 1749 | 4.2900 -0.5900 3.9700 1750 | -3.8700 -0.3700 3.4000 1751 | -1.0700 -0.2800 3.8600 1752 | -0.0800 -0.4600 3.7800 1753 | 2.3900 -0.9400 3.5500 1754 | 3.4400 -1.0400 3.5700 1755 | -6.4400 -3.3300 6.5300 1756 | -4.5500 -0.5000 3.3600 1757 | -2.7900 -0.2900 3.8300 1758 | -1.7500 -0.4000 3.8400 1759 | -0.7100 -0.4900 3.8600 1760 | 0.1300 -0.9400 3.4600 1761 | 2.7200 -1.2300 3.4700 1762 | 3.8900 -1.0900 3.7700 1763 | -6.1100 -3.6800 6.5800 1764 | -5.0300 -0.6400 3.3400 1765 | -3.9900 -0.7500 3.3600 1766 | -2.7400 -0.4800 3.8200 1767 | -1.7000 -0.5800 3.8400 1768 | -0.6600 -0.6800 3.8600 1769 | 0.1800 -1.1400 3.4500 1770 | 2.6600 -1.4100 3.4600 1771 | 3.8300 -1.2700 3.7600 1772 | -7.3900 -2.4600 6.8100 1773 | -6.1100 -0.7000 3.3500 1774 | -5.0800 -0.8100 3.3500 1775 | -4.0400 -0.9200 3.3600 1776 | -2.8000 -0.6600 3.8100 1777 | -1.7600 -0.7600 3.8300 1778 | -0.7200 -0.8600 3.8500 1779 | 0.1400 -1.2900 3.4800 1780 | 2.5100 -1.5600 3.4800 1781 | 3.6600 -1.4600 3.7300 1782 | -6.0700 -3.4500 6.4400 1783 | -6.6700 -0.8100 3.3500 1784 | -5.6400 -0.9200 3.3500 1785 | -4.6000 -1.0200 3.3800 1786 | -3.5700 -1.1400 3.3700 1787 | -2.3300 -0.8900 3.8100 1788 | -1.2900 -0.9900 3.8300 1789 | -0.2700 -1.1200 3.8200 1790 | 0.5700 -1.5800 3.4100 1791 | 2.7900 -1.7300 3.5200 1792 | 3.9800 -1.5600 3.8700 1793 | -8.9400 -3.2000 11.6300 1794 | -6.6200 -0.9900 3.3500 1795 | -5.5900 -1.1100 3.3500 1796 | -4.5000 -1.1200 3.4800 1797 | -3.5200 -1.3300 3.3700 1798 | -2.2800 -1.0700 3.8200 1799 | -1.2400 -1.1700 3.8400 1800 | -0.2200 -1.3100 3.8100 1801 | 0.6200 -1.7600 3.4100 1802 | 2.4100 -1.9000 3.4800 1803 | 3.5700 -1.7800 3.7700 1804 | 4.8400 -1.4700 4.2700 1805 | -6.9600 -1.0900 3.3900 1806 | -5.9500 -1.2400 3.3600 1807 | -4.8900 -1.3000 3.4300 1808 | -3.8100 -1.3300 3.5300 1809 | -2.6500 -1.2300 3.7900 1810 | -1.6100 -1.3200 3.8200 1811 | -0.5700 -1.4200 3.8500 1812 | 0.3000 -1.8200 3.5100 1813 | 1.3200 -1.9600 3.4800 1814 | 2.3600 -2.0600 3.5000 1815 | 3.5300 -1.9300 3.8000 1816 | 4.7900 -1.6300 4.2900 1817 | -7.0100 -1.2400 3.4100 1818 | -6.0000 -1.4100 3.3600 1819 | -4.9100 -1.4200 3.4900 1820 | -3.1100 -1.7300 3.3700 1821 | -1.8700 -1.4800 3.8100 1822 | -0.8300 -1.5800 3.8400 1823 | 0.1200 -1.8400 3.6600 1824 | 1.0500 -2.1300 3.4500 1825 | 2.1000 -2.2300 3.4800 1826 | 3.2600 -2.1000 3.7700 1827 | 4.4900 -1.8600 4.2000 1828 | -5.8800 -3.5000 6.4100 1829 | -6.3500 -1.5300 3.3800 1830 | -5.3400 -1.6700 3.3500 1831 | -2.9400 -1.9000 3.4000 1832 | -1.7200 -1.6700 3.8200 1833 | -0.6700 -1.7700 3.8500 1834 | 0.2700 -2.0400 3.6500 1835 | 1.2100 -2.3200 3.4600 1836 | 2.2600 -2.4000 3.5100 1837 | 3.4700 -2.2000 3.8900 1838 | 4.7100 -1.9500 4.3300 1839 | -4.6300 -4.2100 6.7800 1840 | -6.2000 -1.7200 3.3800 1841 | -5.1800 -1.8600 3.3600 1842 | -2.4100 -1.8000 3.7800 1843 | -1.3500 -1.8800 3.8300 1844 | -0.3100 -1.9800 3.8500 1845 | 0.6100 -2.3000 3.6100 1846 | 1.5700 -2.5300 3.4700 1847 | 2.7200 -2.4400 3.7200 1848 | 3.9200 -2.2600 4.0800 1849 | -7.2400 -2.5700 6.7100 1850 | -6.8200 -1.7300 3.4900 1851 | -5.8400 -1.9400 3.3700 1852 | -3.1500 -2.2400 3.3900 1853 | -1.9300 -2.0100 3.8100 1854 | -0.8900 -2.1100 3.8300 1855 | 0.1500 -2.2100 3.8500 1856 | 1.0500 -2.5600 3.5700 1857 | 2.0500 -2.7400 3.4900 1858 | 3.3100 -2.4400 4.0000 1859 | 4.5200 -2.2400 4.3900 1860 | -7.3700 -2.3400 6.7500 1861 | -6.1900 -2.0600 3.4000 1862 | -5.2100 -2.2600 3.3000 1863 | -2.4100 -2.1600 3.7700 1864 | -1.3500 -2.2400 3.8300 1865 | -0.3100 -2.3300 3.8600 1866 | 0.6900 -2.5100 3.7800 1867 | 1.5800 -2.8800 3.4800 1868 | 2.7600 -2.7400 3.8300 1869 | 4.0000 -2.4800 4.2500 1870 | 3.9000 0.1300 3.9400 1871 | -7.4100 -4.6800 10.9200 1872 | -5.9300 -2.2600 3.4000 1873 | -3.3300 -2.5100 3.4600 1874 | -2.1400 -2.3500 3.8000 1875 | -1.0900 -2.4300 3.8400 1876 | -0.0500 -2.5300 3.8600 1877 | 0.9500 -2.7100 3.8000 1878 | 1.8400 -3.0800 3.4900 1879 | 3.1400 -2.7100 4.0800 1880 | 4.3400 -2.5200 4.4500 1881 | -8.7400 -3.8500 11.5100 1882 | -8.6100 -4.7100 11.3400 1883 | -6.1400 -3.8900 6.7400 1884 | -5.1700 -2.5400 3.3900 1885 | -2.5100 -2.5100 3.7700 1886 | -1.4500 -2.5700 3.8400 1887 | -0.4100 -2.6700 3.8700 1888 | 0.6400 -2.7500 3.9100 1889 | 1.4800 -3.2100 3.5000 1890 | 2.6700 -3.0500 3.8300 1891 | 3.9800 -2.6600 4.4400 1892 | -6.8300 -4.0600 7.2500 1893 | -7.2700 -4.5500 10.8800 1894 | -8.6200 -4.3900 11.3000 1895 | -5.8300 -2.6200 3.4000 1896 | -3.5000 -2.7800 3.5400 1897 | -2.3400 -2.6800 3.8100 1898 | -1.2900 -2.7600 3.8500 1899 | -0.2500 -2.8600 3.8800 1900 | 0.8000 -2.9400 3.9200 1901 | 1.6200 -3.4300 3.4700 1902 | -6.7400 -4.4100 7.6800 1903 | 4.2000 -2.7400 4.5900 1904 | -8.0200 -4.6700 11.0500 1905 | -7.4800 -3.5100 7.4000 1906 | -6.3100 -4.7800 11.2100 1907 | -5.4700 -2.8400 3.3900 1908 | -3.8200 -3.0300 3.4000 1909 | -2.6100 -2.8400 3.7800 1910 | -1.5500 -2.9100 3.8400 1911 | -0.5100 -3.0000 3.8800 1912 | 0.5500 -3.0800 3.9300 1913 | 1.3600 -3.5800 3.4700 1914 | -6.8500 -2.9200 6.5500 1915 | -6.5900 -3.0500 6.4400 1916 | -8.6100 -2.8600 11.2200 1917 | -6.2500 -4.6000 7.7200 1918 | -5.8400 -3.2700 6.2900 1919 | -5.5200 -3.0000 3.4000 1920 | -4.5000 -3.1400 3.3800 1921 | -3.4500 -3.2300 3.4300 1922 | -2.2300 -3.0300 3.8200 1923 | -1.1900 -3.1200 3.8600 1924 | -0.1300 -3.2000 3.9100 1925 | 0.9100 -3.2800 3.9500 1926 | 1.7300 -3.7900 3.4800 1927 | -7.9200 -3.0500 7.6700 1928 | -4.4200 -4.4600 7.1300 1929 | -6.9500 -5.5200 11.2600 1930 | -6.5300 -0.6000 6.2200 1931 | -7.1500 -3.6100 7.1200 1932 | -5.7700 -3.1400 3.4100 1933 | -4.7300 -3.2500 3.4300 1934 | -3.7000 -3.3700 3.4300 1935 | -2.4900 -3.1800 3.8200 1936 | -1.4400 -3.2500 3.8800 1937 | -0.4000 -3.3500 3.9000 1938 | 0.6600 -3.4300 3.9500 1939 | 1.4600 -3.9600 3.4600 1940 | -4.7200 -3.9500 6.4700 1941 | -8.7600 -3.1900 11.4500 1942 | -6.2600 -4.0500 6.9300 1943 | -6.8300 -0.6100 6.3600 1944 | -6.0000 -1.1000 5.9300 1945 | -6.1100 -3.2400 3.4400 1946 | -5.0900 -3.3700 3.4300 1947 | -4.0600 -3.4900 3.4500 1948 | -2.8900 -3.3700 3.7500 1949 | -1.8000 -3.3900 3.8700 1950 | -0.7500 -3.4800 3.9100 1951 | 0.3000 -3.5600 3.9600 1952 | 1.1000 -4.0800 3.4700 1953 | 2.2700 -3.9700 3.7500 1954 | -6.9800 -4.7100 10.9500 1955 | -8.4100 -5.2700 11.5500 1956 | -8.2500 -2.4200 7.7500 1957 | -6.6500 -0.9600 6.1900 1958 | -5.7900 -1.3900 5.8200 1959 | -5.7600 -3.4700 3.4300 1960 | -4.7300 -3.5800 3.4400 1961 | -3.6900 -3.7100 3.4500 1962 | -2.4800 -3.5000 3.8600 1963 | -1.4300 -3.5900 3.9000 1964 | -0.3900 -3.6800 3.9300 1965 | 0.4300 -4.1900 3.4600 1966 | 1.4900 -4.2500 3.5300 1967 | -8.2700 -4.8800 11.1800 1968 | -7.1700 -5.6900 11.4600 1969 | -7.7400 -5.4400 11.4600 1970 | -7.0200 -0.9200 6.3900 1971 | -6.2000 -1.4200 5.9400 1972 | -6.3000 -3.5200 3.4900 1973 | -5.2900 -3.7000 3.4300 1974 | -4.2600 -3.8000 3.4500 1975 | -3.2400 -3.9500 3.4400 1976 | -2.0000 -3.7100 3.8800 1977 | -0.9500 -3.7900 3.9300 1978 | -0.1300 -4.2800 3.4800 1979 | 0.9100 -4.3800 3.5000 1980 | -5.7700 -4.1600 6.8800 1981 | -7.9800 -3.3800 7.8900 1982 | -8.6800 -4.6600 11.4000 1983 | -7.6400 -3.3900 7.5200 1984 | -6.8600 -1.3000 6.1900 1985 | -5.9900 -1.7100 5.8400 1986 | -6.0600 -3.7700 3.4300 1987 | -5.0300 -3.8900 3.4500 1988 | -4.0000 -4.0000 3.4600 1989 | -2.9700 -4.1400 3.4500 1990 | -1.7300 -3.8900 3.9100 1991 | -0.8900 -4.3500 3.5100 1992 | 0.1200 -4.5000 3.4600 1993 | 1.2400 -4.4500 3.6700 1994 | -6.0700 -4.3600 7.2100 1995 | -8.4000 -3.9500 11.2300 1996 | -7.3900 -0.9800 6.7000 1997 | -6.6600 -1.6000 6.0700 1998 | -5.7500 -1.9500 5.8000 1999 | -5.8000 -3.9700 3.4400 2000 | -4.7700 -4.0800 3.4600 2001 | -3.7400 -4.2100 3.4600 2002 | -2.7100 -4.3400 3.4500 2003 | -1.4700 -4.0800 3.9300 2004 | -0.6500 -4.5800 3.4700 2005 | 0.4200 -4.6300 3.5700 2006 | -7.9500 -5.3400 11.3300 2007 | -8.8200 -3.0200 11.4300 2008 | -6.5100 -3.7700 6.8200 2009 | -7.2300 -1.3500 6.4900 2010 | -6.4400 -1.8900 5.9800 2011 | -8.6600 -4.5300 11.3400 2012 | -5.5400 -4.1700 3.4400 2013 | -4.5100 -4.2900 3.4600 2014 | -3.4800 -4.4100 3.4600 2015 | -2.4500 -4.5300 3.4700 2016 | -1.4100 -4.6500 3.4800 2017 | -0.3800 -4.7700 3.4900 2018 | -7.0700 -5.8600 11.7000 2019 | -7.5100 -3.8700 7.7900 2020 | -4.7100 -4.3100 7.0600 2021 | -6.6200 -3.8400 6.9300 2022 | -7.1400 -1.6500 6.3700 2023 | -6.3000 -2.1000 5.9600 2024 | -6.3300 -4.1100 3.6100 2025 | -5.3900 -4.3600 3.4400 2026 | -4.3500 -4.4700 3.4600 2027 | -3.3100 -4.5800 3.4900 2028 | -2.2900 -4.7200 3.4800 2029 | -1.2600 -4.8500 3.4700 2030 | -0.1900 -4.8900 3.5800 2031 | -6.5400 -4.5300 7.7600 2032 | -5.9600 -4.1200 6.8900 2033 | -8.2900 -2.2300 7.7800 2034 | -6.6900 -3.1200 6.5500 2035 | -7.0100 -1.8900 6.3100 2036 | -6.1400 -2.2900 5.9600 2037 | -6.2200 -4.3500 3.5400 2038 | -5.2300 -4.5500 3.4500 2039 | -4.1800 -4.6400 3.4900 2040 | -3.1500 -4.7600 3.5000 2041 | -2.1300 -4.9000 3.4800 2042 | -1.1000 -5.0300 3.4900 2043 | -6.1500 -3.3100 6.4000 2044 | -5.9600 -3.3700 6.3600 2045 | -8.1600 -4.4600 11.0700 2046 | -5.6500 -3.9900 6.6800 2047 | -7.6900 -1.4200 6.9600 2048 | -6.9700 -2.0900 6.2900 2049 | -6.0800 -2.4500 5.9900 2050 | -6.1500 -4.5100 3.5600 2051 | -5.1700 -4.7200 3.4500 2052 | -4.1000 -4.7700 3.5500 2053 | -3.0900 -4.9100 3.5400 2054 | -2.0800 -5.0800 3.4900 2055 | -1.0200 -5.1500 3.5600 2056 | -8.0400 -2.7100 7.6500 2057 | -6.0700 -4.2700 7.1100 2058 | -6.9900 -3.8000 7.1300 2059 | -7.6900 -4.6000 10.9700 2060 | -7.5100 -1.7700 6.7900 2061 | -6.7500 -2.3600 6.2000 2062 | -5.8100 -2.6500 6.0000 2063 | -5.9200 -4.7400 3.5100 2064 | -4.9000 -4.8900 3.4900 2065 | -7.7900 -5.0200 11.0900 2066 | -2.8300 -5.1200 3.5200 2067 | -1.8200 -5.2800 3.4900 2068 | -5.0700 -0.6200 13.9900 2069 | -4.3500 -0.5100 14.6900 2070 | -4.8400 -0.6800 14.4200 2071 | --------------------------------------------------------------------------------